Relationship between hardware interface and controller manager

Hi,

in Unit 4, we self-implemented our own custom controller, and there is a method called update(), does this method have anything to do with the controller manager update step control loop that we were talking about in unit 6?

I know the two things definitely have some connections but I cannot find where did they establish the connection in the source code. So, here comes my first question, where is the connection set in the source code>?
In unit 6, we implemented the hardware interface, and in the launch file rrbot_hw_and_states.launch I noticed that we didn’t specify our controller because the arg is empty
<arg name="controller_to_spawn" default="" />
Here comes my second question:
Why we didn’t specify the controller here as <arg name="controller_to_spawn" default="forward_position_controller" />

Here comes my guess:
My guess is that when we spawn our controller by

<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen"
      args="joint_state_controller $(arg controller_to_spawn)"/>

We kinda tell the hardware interface which controller we are using and when the controller manager update method is called in rrbot_hardware_interface_node, the manager will automatically find the controller that is being used and call its update method. Am I correct?

Hello @yunjinli,

I will answer your first question here.

So, here comes my first question, where is the connection set in the source code?

Let’s start with Unit 4 where you write a custom controller. In that unit you are implementing the method update(). Note that you are implementing this method in a class that inherits from the template class

controller_interface::Controller<
                               hardware_interface::EffortJointInterface>

It turns out that controller_interface::Controller is itself a class derived from the ControllerBase class.

This is where the update() method is originally defined in.

Now let’s continue with Unit 6, where you call the update() method:

When you are calling the update method from your Hardware Abstaction Layer implementation you are calling:

controller_manager::ControllerManager::update

You are bringing it into scope via this statement #include "controller_manager/controller_manager.h" that you see at the top of rrbot_hardware_interface_node.cpp.

You can call that method because you previously created an object of type controller_manager::ControllerManager. To be precise in this line here:

controller_manager::ControllerManager cm(&robot);

This object derives from the template class Controller which itself is derived from the ControllerBase class. And the ControllerBase class is where the update() method is originally defined in. See? It is exactly the same method that you defined in unit 4.

You can see it here:

You can see the original update method defined here:

This is where the template class controller_interface::Controller is defined in the source code:

It takes a bit of detective work to trace the method back, but, yes, it is one and the same method that you are calling.

1 Like

Here I will answer your second question:

Why we didn’t specify the controller here as <arg name="controller_to_spawn" default="forward_position_controller" />

This launch file is loading the hardware interface and also the “joint_state_controller”, which isn’t really a controller, but a broadcaster of the current joint values. It is not loading a controller which you can use to send commands and control the robot. Why?
Because the hardware interface is designed to run with real hardware, and in this case we only have the robot model in Rviz but no real hardware connected. Does this make sense to you?

Also, to verify which controllers are currently loaded you can run:

rosservice call /controller_manager/list_controllers

You should get the response:

controller:
  -
    name: "joint_state_controller"
    state: "running"
    type: "joint_state_controller/JointStateController"
    claimed_resources:
      -
        hardware_interface: "hardware_interface::JointStateInterface"
        resources: []

Which confirm that we only have the “joint_state_controller” loaded.

To load a controller you could do modify the launch file or do it via the command line, for instance:

rosrun controller_manager controller_manager spawn forward_position_controller

To verify which controllers are running use:

rosservice call /controller_manager/list_controllers

You should get the response:

controller:
  -
    name: "joint_state_controller"
    state: "running"
    type: "joint_state_controller/JointStateController"
    claimed_resources:
      -
        hardware_interface: "hardware_interface::JointStateInterface"
        resources: []
  -
    name: "forward_position_controller"
    state: "running"
    type: "position_controllers/JointGroupPositionController"
    claimed_resources:
      -
        hardware_interface: "hardware_interface::PositionJointInterface"
        resources:
          - joint1
          - joint2

Hope this helps!

1 Like

@rzegers Thanks! Now it makes sense to me!

I am happy that I was able to help you.