Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

hardware_components_initial_state doesn't work #1128

Closed
MattiaDeiRossi opened this issue Oct 6, 2023 · 12 comments
Closed

hardware_components_initial_state doesn't work #1128

MattiaDeiRossi opened this issue Oct 6, 2023 · 12 comments

Comments

@MattiaDeiRossi
Copy link

Hi all,

I would to launch ros2_control_node having my hardware component on inactive state as first state.
I read the documentation at https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html that works like

hardware_components_initial_state:
  unconfigured:
    - "arm1"
    - "arm2"
  inactive:
    - "base3"

and my ros2_control description looks like:

<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:macro name="awtube_ros2_control"
    params="use_fake_hardware:=^|true robot_id:=^|awtube brand:=^|synapticon mode_of_op:=^|8">

    <ros2_control name="AwTubeSystem" type="system">
      <hardware>
        <xacro:if value="${use_fake_hardware}">
          <plugin>fake_components/GenericSystem</plugin>
        </xacro:if>
        <xacro:unless value="${use_fake_hardware}">
          <plugin>ethercat_driver/EthercatDriver</plugin>
          <param name="master_id">0</param>
          <param name="control_frequency">1000</param>
        </xacro:unless>
      </hardware>
      .
      .
      .
    </ros2_control>
  </xacro:macro>
</robot>

When writing in my ros2_controller.yam the following code, controllers go immediately in the activate state, and do not stop in the inactive. What am I doing wrong?

controller_manager:
  ros__parameters:
    update_rate: 1000
    hardware_components_initial_state:
      inactive:
      - AwTubeSystem

Thanks

@christophfroehlich
Copy link
Contributor

Hi! Which ROS distro are you using? we renamed fake_components already some time ago and use mock components from humble on.
If you are on <=galactic: We haven't backported the parameter you are trying to use. Be aware of the different versions of the documentation for different releases, there is also a difference of this feature/parameters between humble and rolling.

@MattiaDeiRossi
Copy link
Author

Hi,
Thank you for your answer.
I' m using humble distro. I tried to change <plugin>fake_components/GenericSystem</plugin> into <plugin>mock_components/GenericSystem</plugin> but the behaviour is the same as before.

Could you provide a very simple application example please?

@christophfroehlich
Copy link
Contributor

Have a look on this example how to use the mock_component, but this is not the problem here. (you should have got a warning with humble, that the fake_component is deprecated?).

You write that your controller goes into active state? But the parameter is handling the hardware components.. I'm not sure what the controller_manager is doing with the controller, if the hw component is not in active state.

Try ros2 control list_hardware_components, what does it tell you?

@MattiaDeiRossi
Copy link
Author

I have a look on the example2 using humble version on docker

I haven't any issue if I change

     <hardware>
        <plugin>ros2_control_demo_example_2/DiffBotSystemHardware</plugin>
        <param name="example_param_hw_start_duration_sec">0</param>
        <param name="example_param_hw_stop_duration_sec">3.0</param>
      </hardware> 

with

      <hardware>
        <plugin>fake_components/GenericSystem</plugin>
        <param name="calculate_dynamics">true</param>
      </hardware>

and the same behaviour is using mock_components/GenericSystem.

So regarding the initial state I changed diffbot_controllers.yaml as following

controller_manager:
  ros__parameters:
    update_rate: 10  # Hz
    hardware_components_initial_state:
      unconfigured:
        - "DiffBot"

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    diffbot_base_controller:
      type: diff_drive_controller/DiffDriveController
...

and diffbot.ros2_control.xacro with

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:macro name="diffbot_ros2_control" params="name prefix">

    <ros2_control name="${name}" type="system">
      <!-- <hardware>
        <plugin>ros2_control_demo_example_2/DiffBotSystemHardware</plugin>
        <param name="example_param_hw_start_duration_sec">0</param>
        <param name="example_param_hw_stop_duration_sec">3.0</param>
      </hardware> -->
      <hardware>
        <plugin>mock_components/GenericSystem</plugin>
        <param name="calculate_dynamics">true</param>
      </hardware>
      <joint name="${prefix}left_wheel_joint">
        <command_interface name="velocity"/>
        <state_interface name="position"/>
        <state_interface name="velocity"/>
      </joint>
      <joint name="${prefix}right_wheel_joint">
        <command_interface name="velocity"/>
        <state_interface name="position"/>
        <state_interface name="velocity"/>
      </joint>
    </ros2_control>
  </xacro:macro>
</robot>

I expected Diffbots hardware to be in an unconfigured state, but the command shows

root@docker-desktop:/home/ros2_ws# ros2 launch ros2_control_demo_example_2 diffbot.launch.py
[INFO] [launch]: All log files can be found below /root/.ros/log/2023-10-10-20-30-09-135514-docker-desktop-17079
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [17091]
[INFO] [robot_state_publisher-2]: process started with pid [17093]
[INFO] [spawner-3]: process started with pid [17095]
[robot_state_publisher-2] [WARN] [1696969809.342952800] [kdl_parser]: The root link base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia.  As a workaround, you can add an extra dummy link to your URDF.
[robot_state_publisher-2] [INFO] [1696969809.343017211] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1696969809.343062589] [robot_state_publisher]: got segment caster_frontal_wheel
[robot_state_publisher-2] [INFO] [1696969809.343067245] [robot_state_publisher]: got segment caster_rear_wheel
[robot_state_publisher-2] [INFO] [1696969809.343071055] [robot_state_publisher]: got segment left_wheel
[robot_state_publisher-2] [INFO] [1696969809.343074197] [robot_state_publisher]: got segment right_wheel
[ros2_control_node-1] [INFO] [1696969809.351055073] [resource_manager]: Loading hardware 'DiffBot' 
[ros2_control_node-1] [INFO] [1696969809.351501436] [resource_manager]: Initialize hardware 'DiffBot' 
[ros2_control_node-1] [WARN] [1696969809.351532340] [mock_generic_system]: Parsing of optional initial interface values failed or uses a deprecated format. Add initial values for every state interface in the ros2_control.xacro. For example: 
[ros2_control_node-1] <state_interface name="velocity"> 
[ros2_control_node-1]   <param name="initial_value">0.0</param> 
[ros2_control_node-1] </state_interface>
[ros2_control_node-1] [INFO] [1696969809.351543952] [resource_manager]: Successful initialization of hardware 'DiffBot'
[ros2_control_node-1] [INFO] [1696969809.351574127] [resource_manager]: 'configure' hardware 'DiffBot' 
[ros2_control_node-1] [INFO] [1696969809.351580806] [resource_manager]: Successful 'configure' of hardware 'DiffBot'
[ros2_control_node-1] [INFO] [1696969809.351586369] [resource_manager]: 'activate' hardware 'DiffBot' 
[ros2_control_node-1] [INFO] [1696969809.351591843] [resource_manager]: Successful 'activate' of hardware 'DiffBot'
[ros2_control_node-1] [INFO] [1696969809.355135351] [controller_manager]: update rate is 10 Hz
[ros2_control_node-1] [INFO] [1696969809.355397597] [controller_manager]: RT kernel is recommended for better performance
[ros2_control_node-1] [INFO] [1696969809.700492245] [controller_manager]: Loading controller 'joint_state_broadcaster'
[spawner-3] [INFO] [1696969809.757333591] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1696969809.759182276] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1696969809.759360616] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-3] [INFO] [1696969809.956563556] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[INFO] [spawner-3]: process has finished cleanly [pid 17095]
[INFO] [spawner-4]: process started with pid [17150]
[INFO] [rviz2-5]: process started with pid [17152]
[rviz2-5] QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-root'
[spawner-4] [INFO] [1696969812.295427692] [spawner_diffbot_base_controller]: Waiting for '/controller_manager' node to exist
[ros2_control_node-1] [INFO] [1696969813.305118157] [controller_manager]: Loading controller 'diffbot_base_controller'
[spawner-4] [INFO] [1696969813.356438410] [spawner_diffbot_base_controller]: Loaded diffbot_base_controller
[ros2_control_node-1] [INFO] [1696969813.357631381] [controller_manager]: Configuring controller 'diffbot_base_controller'
[spawner-4] [INFO] [1696969813.556429637] [spawner_diffbot_base_controller]: Configured and activated diffbot_base_controller
[INFO] [spawner-4]: process has finished cleanly [pid 17150]`

and ros2 control list_hardware_components

root@docker-desktop:/home/ros2_ws# ros2 control list_hardware_components
Hardware Component 1
        name: DiffBot
        type: system
        plugin name: mock_components/GenericSystem
        state: id=3 label=active
        command interfaces
                left_wheel_joint/velocity [available] [claimed]
                right_wheel_joint/velocity [available] [claimed]

that seems that hardware component is on active state

@christophfroehlich
Copy link
Contributor

The problem is that the parameter got renamed in rolling but the backport got stuck. Have a look at the docs of the humble branch, you have to use configure_components_on_start unless the changes will be backported.

@MattiaDeiRossi
Copy link
Author

Thank you!

@christophfroehlich
Copy link
Contributor

you're welcome, does it work now?

@MattiaDeiRossi
Copy link
Author

It works now as expected and the hardware component is in the desired state.
In this way happens that ros2_control_node call read() and write() functions automatically and my hardware plugin crashes because it needs to have allocated all interfaces in read() and write().

  1. Is it correct behaviour that read() and write() methods are invoked if hardware is in a different state that active ?
  2. Once the hardware is started in a different state than active, How is it possible to switch its state?

@christophfroehlich
Copy link
Contributor

  1. yes this is intentionally, but confused me in the beginning, too.
  2. There is an old PR for the demos concerning the lifecycle management, updated with this PR. Have a look at this section here, you have to manually call a service of the controller_manager because there is no CLI verb yet.

@Elfits
Copy link

Elfits commented Oct 8, 2024

Dear both,
Sorry to reopen this after a year.
I finally found this issue. But I am still with a similar problem. I need the hardware to be unconfigured on start. I set the hardware_components_initial_state but every time the resource manager configure and activate the hardware automatically. I also checked the source code (Humble) at https://github.com/ros-controls/ros2_control/blob/humble/controller_manager/src/controller_manager.cpp but find out nothing. It seems the code does not work.

As for the aforementioned "configure_components_on_start", I think it is about the inactive state, not the unconfigured state.
So any ideas? Thanks in advance.
I am using ROS2 Humble on Ubuntu22.04, with ros2_control 2.43.1.

Hope this did not bother you. I created a new bug issue at #1780

@saikishor
Copy link
Member

I finally found this issue. But I am still with a similar problem. I need the hardware to be unconfigured on start. I set the hardware_components_initial_state but every time the resource manager configure and activate the hardware automatically. I also checked the source code (Humble) at https://github.com/ros-controls/ros2_control/blob/humble/controller_manager/src/controller_manager.cpp but find out nothing. It seems the code does not work.

@Elfits you can set the components to the unconfigured state using this parameter hardware_components_initial_state.unconfigured

set_components_to_state(
"hardware_components_initial_state.unconfigured",
rclcpp_lifecycle::State(
State::PRIMARY_STATE_UNCONFIGURED, hardware_interface::lifecycle_state_names::UNCONFIGURED));

@Elfits
Copy link

Elfits commented Oct 8, 2024

FYI,

I was surprised to find that when I compiled it myself, the functionality was correct. The hardware can be set to "configured" at the start.
But when I was using ros2_control from direct installation, it failed.

Please see #1780

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants