6 #include    <std_msgs/Int32.h> 
    7 #include    <std_msgs/Int16.h> 
    8 #include    <std_msgs/UInt16.h> 
    9 #include    <std_msgs/Int8.h> 
   10 #include    <std_msgs/String.h> 
   11 #include    <std_msgs/Float64.h> 
   17 #ifdef REACTIVE_RATE_FUNCTION 
   18 #define     CONTROL_WAIT_HZ   (50) 
   19 #define     CONTROL_ACTIVE_HZ (200) 
   21 #define     CONTROL_HZ   (200) 
   29 typedef dynamic_reconfigure::Server<crane_x7_msgs::ServoParameterConfig> 
RECONFIG_TYPE;
 
   52 std::vector<std::string> 
split(
const std::string& input, 
char delimiter)
 
   54     std::istringstream stream(input);
 
   57     std::vector<std::string> result;
 
   58     while (std::getline(stream, field, delimiter)) {
 
   59         result.push_back(field);
 
   67     std::string topic = 
header.at(
"topic");
 
   68     const std_msgs::UInt16ConstPtr& msg = 
event.getMessage();
 
   69     uint16_t set_gain_data = msg->data;
 
   74     std::vector<std::string> topic_list = 
split(topic,
'/');
 
   75     std::string joint_name = topic_list[ topic_list.size()-2 ];
 
   78         if( it->get_joint_name() == joint_name ){
 
   80             set_req_data.
dxl_id = it->get_dxl_id();
 
   81             set_req_data.
gain = set_gain_data;
 
  108             if( it->get_dxl_id() == 
id ){
 
  119                 config.torque_enable     = 
true;
 
  134     std::string current_name;
 
  135     std::string dxl_pos_name;
 
  136     std::string temp_name;
 
  137     std::string gain_name;
 
  138     std::string joint_name;
 
  140     for( std::vector<JOINT_CONTROL>::iterator it=driver->
joints.begin() ; it!=driver->
joints.end() ; ++it ){
 
  141         joint_name = it->get_joint_name();
 
  142         current_name = ( joint_name + 
"/current");
 
  144         dxl_pos_name = ( joint_name + 
"/dxl_position");
 
  146         temp_name = ( joint_name + 
"/temp");
 
  148         gain_name = ( joint_name + 
"/gain");
 
  155     for( std::vector<JOINT_CONTROL>::iterator it=driver->
joints.begin() ; it!=driver->
joints.end() ; ++it ){
 
  157         dynamic_reconfigure::Server<crane_x7_msgs::ServoParameterConfig>::CallbackType 
f;
 
  159         server->setCallback(
f);
 
  160         reconfig_srv.push_back( std::unique_ptr<RECONFIG_TYPE>(server) );
 
  167     std::vector<ros::Publisher>::iterator current_it;
 
  168     std::vector<ros::Publisher>::iterator dxl_pos_it;
 
  169     std::vector<ros::Publisher>::iterator temp_it;
 
  171     std_msgs::Float64 current_out;
 
  172     std_msgs::Int16 dxl_pos_out;
 
  173     std_msgs::Float64 temp_out;
 
  179     for( std::vector<JOINT_CONTROL>::iterator it=driver->
joints.begin() ; it!=driver->
joints.end() ; ++it ){
 
  180         current_out.data = it->get_current();
 
  181         current_it->publish( current_out );
 
  183         dxl_pos_out.data = it->get_dxl_pos();
 
  184         dxl_pos_it->publish( dxl_pos_out );
 
  187             temp_out.data = it->get_temprature();
 
  188             temp_it->publish( temp_out );
 
  196     uint8_t dxl_id = set_param.
dxl_id;
 
  216 int main( 
int argc, 
char* argv[] )
 
  221     std::string config_ns_str;
 
  222     nhPrivate.
getParam(
"config_ns", config_ns_str);
 
  227     if( !setting.
load() ){
 
  233         std::string errorlog;
 
  234         if( crane_x7.
get_error( errorlog ) > 0 ){
 
  235             ROS_INFO(
"Initialize error (%s)",errorlog.c_str());
 
  245 #ifdef REACTIVE_RATE_FUNCTION 
  247     ros::Rate rate_active( CONTROL_ACTIVE_HZ );
 
  256     uint32_t prev_tempCount = 0;
 
  257     bool read_temp_flg = 
false;
 
  270         if( crane_x7.
tempCount != prev_tempCount ){
 
  271             read_temp_flg = 
true;
 
  274             read_temp_flg = 
false;
 
  278         crane_x7.
read( t, 
d );
 
  296         std::string errorlog;
 
  297         while( crane_x7.
get_error( errorlog ) > 0  ){    
 
  302 #ifdef REACTIVE_RATE_FUNCTION