diff --git a/src/safe_cmd_alg_node.cpp b/src/safe_cmd_alg_node.cpp index 30938ba503445761fc79b81d227cab9325c786d2..fced9ffa974913ea484e729f4b34e4c60502a977 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; }