bool LoCoBotController::initSDKHandlers()

in robots/LoCoBot/locobot_control/src/locobot_controller.cpp [296:369]


bool LoCoBotController::initSDKHandlers(void) {
  bool result = false;

  const char *log = NULL;

//  auto it = dynamixel_name_2ids_.begin();

  result = dxl_wb_->addSyncWriteHandler(control_items_["Goal_Position"]->address,
                                        control_items_["Goal_Position"]->data_length,
                                        &log);
  if (!result) {
    ROS_ERROR("%s", log);
    return result;
  } else {
    ROS_INFO("%s", log);
  }

  result = dxl_wb_->addSyncWriteHandler(control_items_["Goal_Velocity"]->address,
                                        control_items_["Goal_Velocity"]->data_length,
                                        &log);
  if (!result) {
    ROS_ERROR("%s", log);
    return result;
  } else {
    ROS_INFO("%s", log);
  }

  if (dxl_wb_->getProtocolVersion() == 2.0f) {
    uint16_t start_address = std::min(control_items_["Present_Position"]->address,
                                      control_items_["Present_Current"]->address);
    uint16_t read_length = control_items_["Present_Position"]->data_length
        + control_items_["Present_Velocity"]->data_length
        + control_items_["Present_Current"]->data_length;
    result = dxl_wb_->addSyncReadHandler(start_address,
                                         read_length,
                                         &log);
    if (!result) {
      ROS_ERROR("%s", log);
      return result;
    }

    start_address = control_items_["Torque_Enable"]->address;
    read_length = control_items_["Torque_Enable"]->data_length;

    result = dxl_wb_->addSyncReadHandler(start_address,
                                         read_length,
                                         &log);
    if (!result) {
      ROS_ERROR("%s", log);
      return result;
    }

    start_address = control_items_["Hardware_Error_Status"]->address;
    read_length = control_items_["Hardware_Error_Status"]->data_length;

    result = dxl_wb_->addSyncReadHandler(start_address,
                                         read_length,
                                         &log);
    if (!result) {
      ROS_ERROR("%s", log);
      return result;
    }

  }

  num_motors_ = 0;
  for (auto const& group:use_group_)
  {
    if (group.second)
      num_motors_ += group_motors_[group.first].size();
  }

  return result;
}