2 #include <std_msgs/String.h> 
   27     std::string device_name;
 
   33     if( device_name.length() > 0 ){
 
   62         ROS_ERROR(
"Undefined key %s.", key_port_name.c_str());
 
   76         ROS_ERROR(
"Undefined key %s.", key_baud_rate.c_str());
 
   80     return (uint32_t)result;
 
   91         ROS_ERROR(
"Undefined key %s.", key_joint_list.c_str());
 
   94             ROS_ERROR(
"XmlRpc get type error! line%d", __LINE__);
 
   96             for( int32_t i = 0; i < load_joints.
size(); ++i ){
 
   98                     ROS_ERROR(
"XmlRpc get type[%d] error! line%d", i, __LINE__);
 
  102                     work.
name = (std::string)joint_name_work;
 
  115     std::string key_joint_param = std::string(
KEY_DXL_PORT) + 
"/";
 
  125     for( 
int jj=0 ; jj<
joint_list.size() ; ++jj ){
 
  126         std::string key_jname = (key_joint_param + 
joint_list[jj].name);
 
  135             ROS_ERROR(
"Undefined joint id key %s. line%d", key_jparam_id.c_str(), __LINE__);
 
  139             ROS_ERROR(
"Undefined joint id key %s. line%d", key_jparam_id.c_str(), __LINE__);
 
  143             ROS_ERROR(
"Undefined joint id key %s. line%d", key_jparam_id.c_str(), __LINE__);
 
  147             ROS_ERROR(
"Undefined joint id key %s. line%d", key_jparam_id.c_str(), __LINE__);
 
  151             ROS_ERROR(
"Undefined joint id key %s. line%d", key_jparam_id.c_str(), __LINE__);