From 34030458cb9be5d4a97dceb93c58bb91807f1647 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= <jvallve@iri.upc.edu> Date: Wed, 23 Oct 2013 15:27:58 +0000 Subject: [PATCH] crashing bugs fixed --- src/safe_cmd_alg_node.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/safe_cmd_alg_node.cpp b/src/safe_cmd_alg_node.cpp index 30938ba..fced9ff 100644 --- a/src/safe_cmd_alg_node.cpp +++ b/src/safe_cmd_alg_node.cpp @@ -73,12 +73,12 @@ void SafeCmdAlgNode::cmd_vel_callback(const geometry_msgs::Twist::ConstPtr& msg) { if(Twist_msg_.linear.x < max_vel_front_ && Twist_msg_.linear.x > max_vel_rear_ ) { - Twist_msg_.linear.x =+ msg->linear.x - last_twist_.linear.x ; - Twist_msg_.linear.y =+ msg->linear.y - last_twist_.linear.y ; - Twist_msg_.linear.z =+ msg->linear.z - last_twist_.linear.z ; - Twist_msg_.angular.x =+ msg->angular.x - last_twist_.angular.x; - Twist_msg_.angular.y =+ msg->angular.y - last_twist_.angular.y; - Twist_msg_.angular.z =+ msg->angular.z - last_twist_.angular.z; + Twist_msg_.linear.y += (msg->linear.y - last_twist_.linear.y ); + Twist_msg_.linear.x += (msg->linear.x - last_twist_.linear.x ); + Twist_msg_.linear.z += (msg->linear.z - last_twist_.linear.z ); + Twist_msg_.angular.x += (msg->angular.x - last_twist_.angular.x); + Twist_msg_.angular.y += (msg->angular.y - last_twist_.angular.y); + Twist_msg_.angular.z += (msg->angular.z - last_twist_.angular.z); } last_twist_= *msg; } -- GitLab