From fc240eff0a9de45b8f0834acaf342858b3812d25 Mon Sep 17 00:00:00 2001 From: Pioneer3 Date: Fri, 28 Sep 2018 17:17:15 +0200 Subject: [PATCH] Small fix in monitoring of clutch state --- RosAria.cpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/RosAria.cpp b/RosAria.cpp index 9568ee1..8b1d299 100644 --- a/RosAria.cpp +++ b/RosAria.cpp @@ -92,9 +92,6 @@ protected: bool userstop_state; bool masterstop_state; - bool clutch_state; - - //Gripper ros::ServiceServer gripper_open_srv; ros::ServiceServer gripper_close_srv; @@ -524,8 +521,6 @@ int RosAriaNode::Setup() userstop_state = false; masterstop_state = false; - clutch_state = true; - // Enable the motors robot->enableMotors(); @@ -560,7 +555,7 @@ void RosAriaNode::publish_robot_info() robot_info_msg.twist.linear.y = robot->getLatVel()/1000.0; robot_info_msg.twist.angular.z = robot->getRotVel()*M_PI/180; robot_info_msg.state.data = robot_state; - robot_info_msg.clutch.data = clutch_state; + robot_info_msg.clutch.data = robot->areMotorsEnabled(); // robot_info_msg.header.stamp = ros::Time::now(); robot_info_pub.publish(robot_info_msg); @@ -911,7 +906,6 @@ void RosAriaNode::clutch_cb(const std_msgs::Bool &msg) robot->lock(); robot->enableMotors(); robot->unlock(); - clutch_state = true; } else { @@ -919,7 +913,6 @@ void RosAriaNode::clutch_cb(const std_msgs::Bool &msg) robot->lock(); robot->disableMotors(); robot->unlock(); - clutch_state = false; } }