From c2141f8dd3bd349f093a3aa01eb0b4db4e14ec70 Mon Sep 17 00:00:00 2001 From: fherrero <fherrero@iri.upc.edu> Date: Wed, 11 Jul 2018 16:39:03 +0200 Subject: [PATCH] Steering msg as UInt8 instead of Int16 --- include/twist_to_manual_control_alg_node.h | 3 ++- src/twist_to_manual_control_alg_node.cpp | 10 +++++----- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/include/twist_to_manual_control_alg_node.h b/include/twist_to_manual_control_alg_node.h index 81dcd97..e244224 100644 --- a/include/twist_to_manual_control_alg_node.h +++ b/include/twist_to_manual_control_alg_node.h @@ -30,6 +30,7 @@ // [publisher subscriber headers] #include <std_msgs/Int16.h> +#include <std_msgs/UInt8.h> #include <geometry_msgs/Twist.h> // [service client headers] @@ -46,7 +47,7 @@ class TwistToManualControlAlgNode : public algorithm_base::IriBaseAlgorithm<Twis // [publisher attributes] ros::Publisher steering_publisher_; - std_msgs::Int16 steering_Int16_msg_; + std_msgs::UInt8 steering_UInt8_msg_; ros::Publisher speed_publisher_; std_msgs::Int16 speed_Int16_msg_; diff --git a/src/twist_to_manual_control_alg_node.cpp b/src/twist_to_manual_control_alg_node.cpp index e3250cb..e69a043 100644 --- a/src/twist_to_manual_control_alg_node.cpp +++ b/src/twist_to_manual_control_alg_node.cpp @@ -7,7 +7,7 @@ TwistToManualControlAlgNode::TwistToManualControlAlgNode(void) : //this->loop_rate_ = 2;//in [Hz] // [init publishers] - this->steering_publisher_ = this->public_node_handle_.advertise<std_msgs::Int16>("steering", 1); + this->steering_publisher_ = this->public_node_handle_.advertise<std_msgs::UInt8>("steering", 1); this->speed_publisher_ = this->public_node_handle_.advertise<std_msgs::Int16>("speed", 1); // [init subscribers] @@ -36,7 +36,7 @@ void TwistToManualControlAlgNode::mainNodeThread(void) // Initialize the topic message structure // Initialize the topic message structure - //this->steering_Int16_msg_.data = my_var; + //this->steering_UInt8_msg_.data = my_var; // Initialize the topic message structure //this->speed_Int16_msg_.data = my_var; @@ -49,7 +49,7 @@ void TwistToManualControlAlgNode::mainNodeThread(void) // [publish messages] // Uncomment the following line to publish the topic message - //this->steering_publisher_.publish(this->steering_Int16_msg_); + //this->steering_publisher_.publish(this->steering_UInt8_msg_); // Uncomment the following line to publish the topic message //this->speed_publisher_.publish(this->speed_Int16_msg_); @@ -95,7 +95,7 @@ void TwistToManualControlAlgNode::cmd_vel_callback(const geometry_msgs::Twist::C steering = (((angular - min_in) * (max_out - min_out)) / (max_in - min_in)) + min_out; - this->steering_Int16_msg_.data = steering; + this->steering_UInt8_msg_.data = steering; //SPEED int speed; @@ -133,7 +133,7 @@ void TwistToManualControlAlgNode::cmd_vel_callback(const geometry_msgs::Twist::C this->speed_Int16_msg_.data = speed; //PUBLISH - this->steering_publisher_.publish(this->steering_Int16_msg_); + this->steering_publisher_.publish(this->steering_UInt8_msg_); this->speed_publisher_.publish(this->speed_Int16_msg_); } -- GitLab