Small fix in monitoring of clutch state

This commit is contained in:
Pioneer3 2018-09-28 17:17:15 +02:00
parent 858cebd7ce
commit fc240eff0a

View File

@ -92,9 +92,6 @@ protected:
bool userstop_state; bool userstop_state;
bool masterstop_state; bool masterstop_state;
bool clutch_state;
//Gripper //Gripper
ros::ServiceServer gripper_open_srv; ros::ServiceServer gripper_open_srv;
ros::ServiceServer gripper_close_srv; ros::ServiceServer gripper_close_srv;
@ -524,8 +521,6 @@ int RosAriaNode::Setup()
userstop_state = false; userstop_state = false;
masterstop_state = false; masterstop_state = false;
clutch_state = true;
// Enable the motors // Enable the motors
robot->enableMotors(); 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.linear.y = robot->getLatVel()/1000.0;
robot_info_msg.twist.angular.z = robot->getRotVel()*M_PI/180; robot_info_msg.twist.angular.z = robot->getRotVel()*M_PI/180;
robot_info_msg.state.data = robot_state; 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_msg.header.stamp = ros::Time::now();
robot_info_pub.publish(robot_info_msg); robot_info_pub.publish(robot_info_msg);
@ -911,7 +906,6 @@ void RosAriaNode::clutch_cb(const std_msgs::Bool &msg)
robot->lock(); robot->lock();
robot->enableMotors(); robot->enableMotors();
robot->unlock(); robot->unlock();
clutch_state = true;
} }
else else
{ {
@ -919,7 +913,6 @@ void RosAriaNode::clutch_cb(const std_msgs::Bool &msg)
robot->lock(); robot->lock();
robot->disableMotors(); robot->disableMotors();
robot->unlock(); robot->unlock();
clutch_state = false;
} }
} }