diff --git a/robotis_controller/include/robotis_controller/robotis_controller.h b/robotis_controller/include/robotis_controller/robotis_controller.h index c2eec4a..6ee5c26 100755 --- a/robotis_controller/include/robotis_controller/robotis_controller.h +++ b/robotis_controller/include/robotis_controller/robotis_controller.h @@ -28,6 +28,7 @@ #include #include #include +#include #include #include #include @@ -38,7 +39,6 @@ #include "robotis_controller_msgs/GetJointModule.h" #include "robotis_controller_msgs/SetJointModule.h" #include "robotis_controller_msgs/SetModule.h" -#include "robotis_controller_msgs/EnableOffset.h" #include "robotis_controller_msgs/LoadOffset.h" #include "robotis_device/robot.h" @@ -142,10 +142,10 @@ public: void setJointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg); void setJointCtrlModuleCallback(const robotis_controller_msgs::JointCtrlModule::ConstPtr &msg); void setCtrlModuleCallback(const std_msgs::String::ConstPtr &msg); + void enableOffsetCallback(const std_msgs::Bool::ConstPtr &msg); bool getJointCtrlModuleService(robotis_controller_msgs::GetJointModule::Request &req, robotis_controller_msgs::GetJointModule::Response &res); bool setJointCtrlModuleService(robotis_controller_msgs::SetJointModule::Request &req, robotis_controller_msgs::SetJointModule::Response &res); bool setCtrlModuleService(robotis_controller_msgs::SetModule::Request &req, robotis_controller_msgs::SetModule::Response &res); - bool enableOffsetService(robotis_controller_msgs::EnableOffset::Request &req, robotis_controller_msgs::EnableOffset::Response &res); bool loadOffsetService(robotis_controller_msgs::LoadOffset::Request &req, robotis_controller_msgs::LoadOffset::Response &res); void gazeboJointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg); diff --git a/robotis_controller/src/robotis_controller/robotis_controller.cpp b/robotis_controller/src/robotis_controller/robotis_controller.cpp index eb8d74e..1e0de91 100755 --- a/robotis_controller/src/robotis_controller/robotis_controller.cpp +++ b/robotis_controller/src/robotis_controller/robotis_controller.cpp @@ -636,6 +636,8 @@ void RobotisController::msgQueueThread() &RobotisController::setControllerModeCallback, this); ros::Subscriber joint_states_sub = ros_node.subscribe("/robotis/set_joint_states", 10, &RobotisController::setJointStatesCallback, this); + ros::Subscriber enable_offset_sub = ros_node.subscribe("/robotis/enable_offset", 10, + &RobotisController::enableOffsetCallback, this); ros::Subscriber gazebo_joint_states_sub; if (gazebo_mode_ == true) @@ -668,8 +670,6 @@ void RobotisController::msgQueueThread() &RobotisController::setJointCtrlModuleService, this); ros::ServiceServer set_module_server = ros_node.advertiseService("/robotis/set_present_ctrl_modules", &RobotisController::setCtrlModuleService, this); - ros::ServiceServer enable_offset_server = ros_node.advertiseService("/robotis/enable_offset", - &RobotisController::enableOffsetService, this); ros::ServiceServer load_offset_server = ros_node.advertiseService("/robotis/load_offset", &RobotisController::loadOffsetService, this); @@ -1735,6 +1735,11 @@ void RobotisController::setJointCtrlModuleCallback(const robotis_controller_msgs set_module_thread_ = boost::thread(boost::bind(&RobotisController::setJointCtrlModuleThread, this, msg)); } +void RobotisController::enableOffsetCallback(const std_msgs::Bool::ConstPtr &msg) +{ + is_offset_enabled_ = (bool)msg->data; +} + bool RobotisController::getJointCtrlModuleService(robotis_controller_msgs::GetJointModule::Request &req, robotis_controller_msgs::GetJointModule::Response &res) { @@ -1790,13 +1795,6 @@ bool RobotisController::setCtrlModuleService(robotis_controller_msgs::SetModule: return true; } -bool RobotisController::enableOffsetService(robotis_controller_msgs::EnableOffset::Request &req, robotis_controller_msgs::EnableOffset::Response &res) -{ - is_offset_enabled_ = (bool)req.enable; - res.result = true; - return true; -} - bool RobotisController::loadOffsetService(robotis_controller_msgs::LoadOffset::Request &req, robotis_controller_msgs::LoadOffset::Response &res) { loadOffset((std::string)req.file_path);