ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Exception while initialising JointGroupVelocityController

asked 2021-08-14 03:31:28 -0500

anthares gravatar image

I am getting this exception while using a JointGroupVelocityController on my bot:

[ros2_control_node-3] [INFO] [1628929019.055107718] [controller_manager]: Loading controller 'velocity_controller'
[ros2_control_node-3] Exception thrown during init stage with message: parameter 'interface_name' has invalid type: cannot undeclare an statically typed parameter 
[ros2_control_node-3] [ERROR] [1628929019.072188078] [controller_manager]: Could not initialize the controller named 'velocity_controller'
[ERROR] [spawner.py-6]: process has died [pid 438850, exit code 1, cmd '/opt/ros/rolling/lib/controller_manager/spawner.py velocity_controller --ros-args'].

My start control_manager using this configuration:

controller_manager:
  ros__parameters:
    update_rate: 100  # Hz

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster
    velocity_controller:
      type: velocity_controllers/JointGroupVelocityController

velocity_controller:
    ros__parameters:
        joints:
          - head_joint

The joint definition looks like:

<joint name="${prefix}${delimiter}head_joint" type="revolute">
  <parent link="${prefix}${delimiter}base_link"/>
  <child link="${prefix}${delimiter}head_link"/>
  <origin xyz="0 ${base_length/2 + head_length/2} ${(head_height/2 - base_height/2)}" rpy="0 0 0"/>
  <limit lower="0" upper="0.3" effort="10" velocity="3"/>
  <axis xyz="1 0 0"/>
</joint>

and these are the interfaces defined for ros2_control:

  <joint name="${prefix}${delimiter}head_joint">

    <command_interface name="velocity">
      <param name="min">-1</param>
      <param name="max">1</param>
    </command_interface>
    <command_interface name="position">
      <param name="min">-1</param>
      <param name="max">1</param>
    </command_interface>
    <command_interface name="acceleration">
      <param name="min">-1</param>
      <param name="max">1</param>
    </command_interface>

    <state_interface name="acceleration" />
    <state_interface name="position"/>
    <state_interface name="velocity"/>
  </joint>

My ros2_control hardware exports those interfaces:

  std::vector<hardware_interface::StateInterface> ServoSystemHardware::export_state_interfaces()
    {
      std::vector<hardware_interface::StateInterface> state_interfaces;
      for (size_t i = 0; i < info_.joints.size(); i++)
      {
        state_interfaces.emplace_back(hardware_interface::StateInterface(info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_positions_[i]));
        state_interfaces.emplace_back(hardware_interface::StateInterface(info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_velocities_[i]));
        state_interfaces.emplace_back(hardware_interface::StateInterface(info_.joints[i].name, hardware_interface::HW_IF_ACCELERATION, &hw_accelerations_[i]));
      }

      RCLCPP_INFO(rclcpp::get_logger("ServoSystemHardware"), "State interfaces exported.");

      return state_interfaces;
    }

and commands:

  command_interfaces.emplace_back(hardware_interface::CommandInterface(info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_positions_commands_[i]));
  command_interfaces.emplace_back(hardware_interface::CommandInterface(info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_velocities_commands_[i]));
  command_interfaces.emplace_back(hardware_interface::CommandInterface(info_.joints[i].name, hardware_interface::HW_IF_ACCELERATION, &hw_accelerations_commands_[i]));

I cannot figure out where that exception is coming from and the reason why it is fired. Anyone got any idea?

Thanks.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-08-14 03:45:57 -0500

gvdhoorn gravatar image

It's likely this is (related to) ros-controls/ros2_controllers#221.

edit flag offensive delete link more

Comments

@gdvhoorn yes, you are absolutely right. The code throws the exception on:

// undeclare interface parameter used in the general forward_command_controller
get_node()->undeclare_parameter("interface_name");
anthares gravatar image anthares  ( 2021-08-14 03:52:11 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-08-14 03:31:28 -0500

Seen: 106 times

Last updated: Aug 14 '21