@@ -499,7 +499,7 @@ void RobotisController::initializeDevice(const std::string init_file_path)
499
499
bulkread_data_length += addr_leng;
500
500
for (int l = 0 ; l < addr_leng; l++)
501
501
{
502
- // ROS_WARN("[%12s] INDIR_ADDR: %d, ITEM_ADDR: %d", joint_name.c_str(), indirect_addr, dxl->ctrl_table [dxl->bulk_read_items [i]->item_name ]->address + _l );
502
+ // ROS_WARN("[%12s] INDIR_ADDR: %d, ITEM_ADDR: %d", joint_name.c_str(), indirect_addr, dxl->ctrl_table_ [dxl->bulk_read_items_ [i]->item_name_ ]->address_ + l );
503
503
read2Byte (joint_name, indirect_addr, &data16);
504
504
if (data16 != dxl->ctrl_table_ [dxl->bulk_read_items_ [i]->item_name_ ]->address_ + l)
505
505
{
@@ -946,8 +946,8 @@ void RobotisController::process()
946
946
dxl->dxl_state_ ->goal_velocity_ = dxl->convertValue2Velocity (data);
947
947
else if (dxl->goal_current_item_ != 0 && item->item_name_ == dxl->goal_current_item_ ->item_name_ )
948
948
dxl->dxl_state_ ->goal_torque_ = dxl->convertValue2Torque (data);
949
- else
950
- dxl->dxl_state_ ->bulk_read_table_ [item->item_name_ ] = data;
949
+
950
+ dxl->dxl_state_ ->bulk_read_table_ [item->item_name_ ] = data;
951
951
}
952
952
}
953
953
@@ -1166,8 +1166,8 @@ void RobotisController::process()
1166
1166
dxl->dxl_state_ ->goal_velocity_ = dxl->convertValue2Velocity (data);
1167
1167
else if (dxl->goal_current_item_ != 0 && item->item_name_ == dxl->goal_current_item_ ->item_name_ )
1168
1168
dxl->dxl_state_ ->goal_torque_ = dxl->convertValue2Torque (data);
1169
- else
1170
- dxl->dxl_state_ ->bulk_read_table_ [item->item_name_ ] = data;
1169
+
1170
+ dxl->dxl_state_ ->bulk_read_table_ [item->item_name_ ] = data;
1171
1171
}
1172
1172
}
1173
1173
@@ -1251,7 +1251,7 @@ void RobotisController::process()
1251
1251
1252
1252
if (result_state == NULL )
1253
1253
{
1254
- fprintf (stderr, " [%s] %s" , (*module_it)->getModuleName ().c_str (), joint_name.c_str ());
1254
+ ROS_ERROR ( " [%s] %s " , (*module_it)->getModuleName ().c_str (), joint_name.c_str ());
1255
1255
continue ;
1256
1256
}
1257
1257
0 commit comments