From ec79a83e61b9bbe53984cad742b9e4065cfbf65d Mon Sep 17 00:00:00 2001
From: fherrero <fherrero@iri.upc.edu>
Date: Mon, 18 Jun 2018 17:07:43 +0200
Subject: [PATCH] Updated seat_car_controller steering and steering angle
 message types, to match model_car (odometry) packages last version (v3.1)

---
 seat_car_controller/include/seat_car_controller.h      | 2 +-
 seat_car_controller/include/seat_car_controller_impl.h | 6 +++---
 2 files changed, 4 insertions(+), 4 deletions(-)

diff --git a/seat_car_controller/include/seat_car_controller.h b/seat_car_controller/include/seat_car_controller.h
index d867145..1ad5209 100644
--- a/seat_car_controller/include/seat_car_controller.h
+++ b/seat_car_controller/include/seat_car_controller.h
@@ -49,7 +49,7 @@ namespace seat_car_controller
     private:
       // action subscriber
       ros::Subscriber steering_sub;
-      void steering_callback(const std_msgs::Int16::ConstPtr& msg);
+      void steering_callback(const std_msgs::UInt8::ConstPtr& msg);
       ros::Subscriber speed_sub;
       void speed_callback(const std_msgs::Int16::ConstPtr& msg);
       ros::Subscriber imu_sub;
diff --git a/seat_car_controller/include/seat_car_controller_impl.h b/seat_car_controller/include/seat_car_controller_impl.h
index 6711782..a5b4a0e 100644
--- a/seat_car_controller/include/seat_car_controller_impl.h
+++ b/seat_car_controller/include/seat_car_controller_impl.h
@@ -254,7 +254,7 @@ namespace seat_car_controller
 
       this->yaw_pub = root_nh.advertise<std_msgs::Float32>(this->yaw_topic,1);
       this->twist_pub = root_nh.advertise<geometry_msgs::Twist>(this->twist_topic,1);
-      this->steer_angle_pub = root_nh.advertise<std_msgs::UInt8>(this->steering_fb_topic,1);
+      this->steer_angle_pub = root_nh.advertise<std_msgs::UInt16>(this->steering_fb_topic,1);
 
       this->last_cmd_drive=0.0;
       this->last_cmd_steer=0.0;
@@ -272,7 +272,7 @@ namespace seat_car_controller
       static double yaw=0.0;
       static double last_steer_angle=0.0;
       geometry_msgs::Twist twist_msg;
-      std_msgs::UInt8 steer_angle_msg;
+      std_msgs::UInt16 steer_angle_msg;
 
       steer_l_pos=this->joints_[0].getPosition();
       steer_r_pos=this->joints_[1].getPosition();
@@ -362,7 +362,7 @@ namespace seat_car_controller
     }
 
   template <class HardwareInterface>
-    void SeatCarController<HardwareInterface>::steering_callback(const std_msgs::Int16::ConstPtr& msg)
+    void SeatCarController<HardwareInterface>::steering_callback(const std_msgs::UInt8::ConstPtr& msg)
     {
       double servo_angle=(msg->data-this->zero_steer_angle)*3.14159/180.0;
       double car_angle;
-- 
GitLab