Controller manager not available

Hello,

I’ve tried to complete unit 3 ( Hardware Interface Implementation Template) but it seems like the controller manager not working right?

Followed unit 3, three times now and I get the same result every time. Robot not launching correctly, only first joint stands up right, the other just hangs there.

user:~/ros2_ws$ source install/setup.bash
user:~/ros2_ws$ ros2 launch my_robot_hardware_interface bring_up_on_hardware.launch.py

[INFO] [launch]: All log files can be found below /home/user/.ros/log/2022-07-19-16-39-09-182794-4_xterm-4451
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [4453]
[INFO] [spawner-2]: process started with pid [4455]
[INFO] [spawner-3]: process started with pid [4457]
[INFO] [spawner-4]: process started with pid [4459]
[INFO] [robot_state_publisher-5]: process started with pid [4461]
[INFO] [rviz2-6]: process started with pid [4463]
[ros2_control_node-1] terminate called after throwing an instance of 'pluginlib::LibraryLoadException'
[ros2_control_node-1]   what():  Failed to load library /home/user/ros2_ws/install/my_robot_hardware_interface/lib/libmy_robot_hardware_interface.so. Make sure that you are calling thePLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library dlopen error: /home/user/ros2_ws/install/my_robot_hardware_interface/lib/libmy_robot_hardware_interface.so: undefined symbol: _ZN26ros2_control_demo_hardware31RRBotSystemPositionOnlyHardware13on_deactivateERKN16rclcpp_lifecycle5StateE, at /tmp/binarydeb/ros-galactic-rcutils-4.0.2/src/shared_library.c:99
[robot_state_publisher-5] Link link1 had 1 children
[robot_state_publisher-5] Link link2 had 1 children
[robot_state_publisher-5] Link link3 had 1 children
[robot_state_publisher-5] Link camera_link had 1 children
[robot_state_publisher-5] Link camera_link_optical had 0 children
[robot_state_publisher-5] [INFO] [1658248749.669679964] [robot_state_publisher]: got segment camera_link
[robot_state_publisher-5] [INFO] [1658248749.669786548] [robot_state_publisher]: got segment camera_link_optical
[robot_state_publisher-5] [INFO] [1658248749.669812695] [robot_state_publisher]: got segment link1
[robot_state_publisher-5] [INFO] [1658248749.669830825] [robot_state_publisher]: got segment link2
[robot_state_publisher-5] [INFO] [1658248749.669847548] [robot_state_publisher]: got segment link3
[robot_state_publisher-5] [INFO] [1658248749.669863990] [robot_state_publisher]: got segment world
[ERROR] [ros2_control_node-1]: process has died [pid 4453, exit code -6, cmd '/opt/ros/galactic/lib/controller_manager/ros2_control_node --ros-args --params-file /tmp/launch_params_8gt24rv4 --params-file /home/user/ros2_ws/install/my_robot_hardware_interface/share/my_robot_hardware_interface/config/controller_configuration.yaml'].
[spawner-4] [INFO] [1658248750.152696598] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1658248750.221954547] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [INFO] [1658248750.232681563] [spawner_forward_position_controller]: Waiting for /controller_manager services
[spawner-4] [INFO] [1658248752.161627139] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1658248752.230794321] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [INFO] [1658248752.240980260] [spawner_forward_position_controller]: Waiting for /controller_manager services
[spawner-4] [INFO] [1658248754.170799691] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1658248754.240021384] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [INFO] [1658248754.249834550] [spawner_forward_position_controller]: Waiting for /controller_manager services
[spawner-4] [INFO] [1658248756.180545332] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1658248756.249374193] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [INFO] [1658248756.257891518] [spawner_forward_position_controller]: Waiting for /controller_manager services
[spawner-4] [INFO] [1658248758.190055589] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1658248758.258498090] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [INFO] [1658248758.267030351] [spawner_forward_position_controller]: Waiting for /controller_manager services
[spawner-4] [ERROR] [1658248760.199021577] [spawner_joint_trajectory_controller]: Controller manager not available
[spawner-2] [ERROR] [1658248760.267442958] [spawner_joint_state_broadcaster]: Controller manager not available
[spawner-3] [ERROR] [1658248760.275913201] [spawner_forward_position_controller]: Controller manager not available
[ERROR] [spawner-4]: process has died [pid 4459, exit code 1, cmd '/opt/ros/galactic/lib/controller_manager/spawner joint_trajectory_controller -c /controller_manager --ros-args'].
[ERROR] [spawner-2]: process has died [pid 4455, exit code 1, cmd '/opt/ros/galactic/lib/controller_manager/spawner joint_state_broadcaster --controller-manager /controller_manager --ros-args'].
[ERROR] [spawner-3]: process has died [pid 4457, exit code 1, cmd '/opt/ros/galactic/lib/controller_manager/spawner forward_position_controller -c /controller_manager –ros-args'].

From what i understand it seems like there is a problem with the controller manage not being available.

I also tried to list the controllers:

user:~/ros2_ws$ ros2 control list_controllers
Could not contact service /controller_manager/list_controllers
user:~/ros2_ws$ ros2 control
list_controller_types        list_hardware_interfaces     reload_controller_libraries  switch_controllers
list_controllers             load_controller              set_controller_state         unload_controller
user:~/ros2_ws$ ros2 control reload_controller_libraries
Could not contact service /controller_manager/reload_controller_libraries

Thanks for considering this.

Hello @vetle.tjohansen,

by going through the console output it looks like the controller manager is crashing because it can’t find the plugin that implements the hardware interface.

These two lines from the console output gives us some hints:

Could you please check that you have included the PLUGINLIB_EXPORT_CLASS macro at the bottom of my_robot_hardware_interface.cpp? Could you please also paste that part here so that I can have a look at it.

Additionally could you please post the content of my_robot_hardware_interface.xml to verify the names are consistent?

Cheers, Roberto

Hello,

Thanks for the fast reply.

Check of my_robot_hardware_interface.cpp:

Here is the whole code:

#include "my_robot_hardware_interface/my_robot_hardware_interface.hpp"

#include <chrono>
#include <cmath>
#include <limits>
#include <memory>
#include <vector>

#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/rclcpp.hpp"

namespace ros2_control_demo_hardware {
CallbackReturn RRBotSystemPositionOnlyHardware::on_init(
    const hardware_interface::HardwareInfo &info) {
  if (hardware_interface::SystemInterface::on_init(info) !=
      CallbackReturn::SUCCESS) {
    return CallbackReturn::ERROR;
  }

  // START: This part here is for exemplary purposes - Please do not copy to
  // your production code
  hw_start_sec_ =
      stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
  hw_stop_sec_ =
      stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
  hw_slowdown_ = stod(info_.hardware_parameters["example_param_hw_slowdown"]);
  // END: This part here is for exemplary purposes - Please do not copy to your
  // production code
  hw_states_.resize(info_.joints.size(),
                    std::numeric_limits<double>::quiet_NaN());
  hw_commands_.resize(info_.joints.size(),
                      std::numeric_limits<double>::quiet_NaN());

  for (const hardware_interface::ComponentInfo &joint : info_.joints) {
    // RRBotSystemPositionOnly has exactly one state and command interface on
    // each joint
    if (joint.command_interfaces.size() != 1) {
      RCLCPP_FATAL(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
                   "Joint '%s' has %zu command interfaces found. 1 expected.",
                   joint.name.c_str(), joint.command_interfaces.size());
      return CallbackReturn::ERROR;
    }

    if (joint.command_interfaces[0].name !=
        hardware_interface::HW_IF_POSITION) {
      RCLCPP_FATAL(
          rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
          "Joint '%s' have %s command interfaces found. '%s' expected.",
          joint.name.c_str(), joint.command_interfaces[0].name.c_str(),
          hardware_interface::HW_IF_POSITION);
      return CallbackReturn::ERROR;
    }

    if (joint.state_interfaces.size() != 1) {
      RCLCPP_FATAL(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
                   "Joint '%s' has %zu state interface. 1 expected.",
                   joint.name.c_str(), joint.state_interfaces.size());
      return CallbackReturn::ERROR;
    }

    if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) {
      RCLCPP_FATAL(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
                   "Joint '%s' have %s state interface. '%s' expected.",
                   joint.name.c_str(), joint.state_interfaces[0].name.c_str(),
                   hardware_interface::HW_IF_POSITION);
      return CallbackReturn::ERROR;
    }
  }

  return CallbackReturn::SUCCESS;
}

CallbackReturn RRBotSystemPositionOnlyHardware::on_configure(
    const rclcpp_lifecycle::State &previous_state) {
  // START: This part here is for exemplary purposes - Please do not copy to
  // your production code

  // prevent unused variable warning
  auto prev_state = previous_state;
  RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
              "Configuring ...please wait...");

  for (int i = 0; i < hw_start_sec_; i++) {
    rclcpp::sleep_for(std::chrono::seconds(1));
    RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
                "%.1f seconds left...", hw_start_sec_ - i);
  }
  // END: This part here is for exemplary purposes - Please do not copy to your
  // production code

  // reset values always when configuring hardware
  for (uint i = 0; i < hw_states_.size(); i++) {
    hw_states_[i] = 0;
    hw_commands_[i] = 0;
  }

  RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
              "Successfully configured!");

  return CallbackReturn::SUCCESS;
}

std::vector<hardware_interface::StateInterface>
RRBotSystemPositionOnlyHardware::export_state_interfaces() {
  std::vector<hardware_interface::StateInterface> state_interfaces;
  for (uint i = 0; i < info_.joints.size(); i++) {
    state_interfaces.emplace_back(hardware_interface::StateInterface(
        info_.joints[i].name, hardware_interface::HW_IF_POSITION,
        &hw_states_[i]));
  }

  return state_interfaces;
}

std::vector<hardware_interface::CommandInterface>
RRBotSystemPositionOnlyHardware::export_command_interfaces() {
  std::vector<hardware_interface::CommandInterface> command_interfaces;
  for (uint i = 0; i < info_.joints.size(); i++) {
    command_interfaces.emplace_back(hardware_interface::CommandInterface(
        info_.joints[i].name, hardware_interface::HW_IF_POSITION,
        &hw_commands_[i]));
  }

  return command_interfaces;
}

CallbackReturn RRBotSystemPositionOnlyHardware::on_activate(
    const rclcpp_lifecycle::State & /*previous_state*/) {
  // START: This part here is for exemplary purposes - Please do not copy it to
  // your production code
  RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
              "Activating ...please wait...");

  for (int i = 0; i < hw_start_sec_; i++) {
    rclcpp::sleep_for(std::chrono::seconds(1));
    RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
                "%.1f seconds left...", hw_start_sec_ - i);
  }
  // END: This part here is for exemplary purposes - Please do not copy to your
  // production code

  // command and state should be equal when starting
  for (uint i = 0; i < hw_states_.size(); i++) {
    hw_commands_[i] = hw_states_[i];
  }

  RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
              "Successfully activated!");

  return CallbackReturn::SUCCESS;
}

hardware_interface::return_type RRBotSystemPositionOnlyHardware::read() {
  // START: This part here is for exemplary purposes - Please do not copy to
  // your production code
  RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
              "Reading...");

  for (uint i = 0; i < hw_states_.size(); i++) {
    // Simulate RRBot's movement
    hw_states_[i] =
        hw_states_[i] + (hw_commands_[i] - hw_states_[i]) / hw_slowdown_;
    RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
                "Got state %.5f for joint %d!", hw_states_[i], i);
  }
  RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
              "Joints successfully read!");
  // END: This part here is for exemplary purposes - Please do not copy to your
  // production code

  return hardware_interface::return_type::OK;
}

hardware_interface::return_type RRBotSystemPositionOnlyHardware::write() {
  // START: This part here is for exemplary purposes - Please do not copy to
  // your production code
  RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
              "Writing...");

  for (uint i = 0; i < hw_commands_.size(); i++) {
    // Simulate sending commands to the hardware
    RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
                "Got command %.5f for joint %d!", hw_commands_[i], i);
  }
  RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
              "Joints successfully written!");
  // END: This part here is for exemplary purposes - Please do not copy to your
  // production code

  return hardware_interface::return_type::OK;
}

} // namespace ros2_control_demo_hardware

#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(
    ros2_control_demo_hardware::RRBotSystemPositionOnlyHardware,
    hardware_interface::SystemInterface)

Content of my_robot_hardware_interface.xml:

<library path="my_robot_hardware_interface">
  <class name="ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware"
         type="ros2_control_demo_hardware::RRBotSystemPositionOnlyHardware"
         base_class_type="hardware_interface::SystemInterface">
    <description>
      ros2_control minimal hardware interface template
    </description>
  </class>
</library>

Hello @vetle.tjohansen,

from the code you posted I can see that the implementation of the on_deactivate method is missing.

Please add the method implementation as described under 3.11 Write the on_deactivate() method.

Then save, compile and source to see if this solves the problem.

Regards,

Roberto

This topic was automatically closed 7 days after the last reply. New replies are no longer allowed.