Skip to content

Commit 297ca13

Browse files
Fix CLI load_controller verb (ros-controls#585)
1 parent 25c1f59 commit 297ca13

File tree

7 files changed

+198
-37
lines changed

7 files changed

+198
-37
lines changed

example_1/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ if(BUILD_TESTING)
7676
ament_add_pytest_test(example_1_urdf_xacro test/test_urdf_xacro.py)
7777
ament_add_pytest_test(view_example_1_launch test/test_view_robot_launch.py)
7878
ament_add_pytest_test(run_example_1_launch test/test_rrbot_launch.py)
79+
ament_add_pytest_test(run_example_1_launch_cli_direct test/test_rrbot_launch_cli_direct.py)
7980
endif()
8081

8182

example_1/bringup/config/rrbot_controllers.yaml

Lines changed: 0 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -13,27 +13,3 @@ forward_position_controller:
1313
- joint1
1414
- joint2
1515
interface_name: position
16-
17-
18-
joint_trajectory_position_controller:
19-
ros__parameters:
20-
type: joint_trajectory_controller/JointTrajectoryController
21-
22-
joints:
23-
- joint1
24-
- joint2
25-
26-
command_interfaces:
27-
- position
28-
29-
state_interfaces:
30-
- position
31-
32-
action_monitor_rate: 20.0 # Defaults to 20
33-
34-
allow_partial_joints_goal: false # Defaults to false
35-
open_loop_control: true
36-
allow_integration_in_goal_trajectories: true
37-
constraints:
38-
stopped_velocity_tolerance: 0.01 # Defaults to 0.01
39-
goal_time: 0.0 # Defaults to 0.0 (start immediately)
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
joint_trajectory_position_controller:
2+
ros__parameters:
3+
type: joint_trajectory_controller/JointTrajectoryController
4+
5+
joints:
6+
- joint1
7+
- joint2
8+
9+
command_interfaces:
10+
- position
11+
12+
state_interfaces:
13+
- position
14+
15+
action_monitor_rate: 20.0 # Defaults to 20
16+
17+
allow_partial_joints_goal: false # Defaults to false
18+
open_loop_control: true
19+
allow_integration_in_goal_trajectories: true
20+
constraints:
21+
stopped_velocity_tolerance: 0.01 # Defaults to 0.01
22+
goal_time: 0.0 # Defaults to 0.0 (start immediately)

example_1/doc/userdoc.rst

Lines changed: 9 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -241,15 +241,15 @@ Tutorial steps
241241

242242
.. code-block:: shell
243243
244-
ros2 control load_controller joint_trajectory_position_controller
244+
ros2 control load_controller joint_trajectory_position_controller $(ros2 pkg prefix ros2_control_demo_example_1 --share)/config/rrbot_jtc.yaml
245245
246246
.. group-tab:: Docker
247247

248248
(from the docker terminal, see above)
249249

250250
.. code-block:: shell
251251
252-
ros2 control load_controller joint_trajectory_position_controller
252+
ros2 control load_controller joint_trajectory_position_controller $(ros2 pkg prefix ros2_control_demo_example_1 --share)/config/rrbot_jtc.yaml
253253
254254
what should return ``Successfully loaded controller joint_trajectory_position_controller``. Check the status with
255255

@@ -297,11 +297,6 @@ Tutorial steps
297297
298298
what should give ``Successfully configured joint_trajectory_position_controller``.
299299

300-
.. note::
301-
302-
The parameters are already set in `rrbot_controllers.yaml <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_1/bringup/config/rrbot_controllers.yaml>`__
303-
but the controller was not loaded from the `launch file rrbot.launch.py <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_1/bringup/launch/rrbot.launch.py>`__ before.
304-
305300
As an alternative, you can load the controller directly in ``inactive``-state by means of the option for ``load_controller`` with
306301

307302
.. tabs::
@@ -310,15 +305,15 @@ Tutorial steps
310305

311306
.. code-block:: shell
312307
313-
ros2 control load_controller joint_trajectory_position_controller --set-state inactive
308+
ros2 control load_controller --set-state inactive joint_trajectory_position_controller $(ros2 pkg prefix ros2_control_demo_example_1 --share)/config/rrbot_jtc.yaml
314309
315310
.. group-tab:: Docker
316311

317312
(from the docker terminal, see above)
318313

319314
.. code-block:: shell
320315
321-
ros2 control load_controller joint_trajectory_position_controller --set-state inactive
316+
ros2 control load_controller --set-state inactive joint_trajectory_position_controller $(ros2 pkg prefix ros2_control_demo_example_1 --share)/config/rrbot_jtc.yaml
322317
323318
You should get the result ``Successfully loaded controller joint_trajectory_position_controller into state inactive``.
324319

@@ -436,7 +431,11 @@ Files used for this demos
436431
-------------------------
437432

438433
* Launch file: `rrbot.launch.py <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_1/bringup/launch/rrbot.launch.py>`__
439-
* Controllers yaml: `rrbot_controllers.yaml <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_1/bringup/config/rrbot_controllers.yaml>`__
434+
* Controllers yaml:
435+
436+
* `rrbot_controllers.yaml <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_1/bringup/config/rrbot_controllers.yaml>`__
437+
* `rrbot_jtc.yaml <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_1/bringup/config/rrbot_jtc.yaml>`__
438+
440439
* URDF file: `rrbot.urdf.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_1/description/urdf/rrbot.urdf.xacro>`__
441440

442441
* Description: `rrbot_description.urdf.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/ros2_control_demo_description/rrbot/urdf/rrbot_description.urdf.xacro>`__

example_1/test/test_rrbot_launch.py

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
import os
3232
import pytest
3333
import unittest
34+
import subprocess
3435

3536
from ament_index_python.packages import get_package_share_directory
3637
from launch import LaunchDescription
@@ -89,6 +90,53 @@ def test_check_if_msgs_published(self):
8990
check_if_js_published("/joint_states", ["joint1", "joint2"])
9091

9192

93+
class TestFixtureCLI(unittest.TestCase):
94+
95+
def setUp(self):
96+
rclpy.init()
97+
self.node = Node("test_node")
98+
99+
def tearDown(self):
100+
self.node.destroy_node()
101+
rclpy.shutdown()
102+
103+
def test_main(self, proc_output):
104+
105+
# Command to run the CLI
106+
cname = "joint_trajectory_position_controller"
107+
command = [
108+
"ros2",
109+
"control",
110+
"load_controller",
111+
cname,
112+
os.path.join(
113+
get_package_share_directory("ros2_control_demo_example_1"),
114+
"config/rrbot_jtc.yaml",
115+
),
116+
]
117+
subprocess.run(command, check=True)
118+
check_controllers_running(self.node, [cname], state="unconfigured")
119+
check_controllers_running(self.node, ["forward_position_controller"], state="active")
120+
121+
command = ["ros2", "control", "set_controller_state", cname, "inactive"]
122+
subprocess.run(command, check=True)
123+
check_controllers_running(self.node, [cname], state="inactive")
124+
check_controllers_running(self.node, ["forward_position_controller"], state="active")
125+
126+
command = [
127+
"ros2",
128+
"control",
129+
"set_controller_state",
130+
"forward_position_controller",
131+
"inactive",
132+
]
133+
subprocess.run(command, check=True)
134+
command = ["ros2", "control", "set_controller_state", cname, "active"]
135+
subprocess.run(command, check=True)
136+
check_controllers_running(self.node, ["forward_position_controller"], state="inactive")
137+
check_controllers_running(self.node, [cname], state="active")
138+
139+
92140
# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
93141
# @launch_testing.post_shutdown_test()
94142
# # These tests are run after the processes in generate_test_description() have shutdown.
Lines changed: 115 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,115 @@
1+
# Copyright (c) 2024 AIT - Austrian Institute of Technology GmbH
2+
#
3+
# Redistribution and use in source and binary forms, with or without
4+
# modification, are permitted provided that the following conditions are met:
5+
#
6+
# * Redistributions of source code must retain the above copyright
7+
# notice, this list of conditions and the following disclaimer.
8+
#
9+
# * Redistributions in binary form must reproduce the above copyright
10+
# notice, this list of conditions and the following disclaimer in the
11+
# documentation and/or other materials provided with the distribution.
12+
#
13+
# * Neither the name of the {copyright_holder} nor the names of its
14+
# contributors may be used to endorse or promote products derived from
15+
# this software without specific prior written permission.
16+
#
17+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
# POSSIBILITY OF SUCH DAMAGE.
28+
#
29+
# Author: Christoph Froehlich
30+
31+
import os
32+
import pytest
33+
import unittest
34+
import subprocess
35+
36+
from ament_index_python.packages import get_package_share_directory
37+
from launch import LaunchDescription
38+
from launch.actions import IncludeLaunchDescription
39+
from launch.launch_description_sources import PythonLaunchDescriptionSource
40+
from launch_testing.actions import ReadyToTest
41+
42+
# import launch_testing.markers
43+
import rclpy
44+
from rclpy.node import Node
45+
from ros2_control_demo_testing.test_utils import check_controllers_running
46+
47+
48+
# Executes the given launch file and checks if all nodes can be started
49+
@pytest.mark.rostest
50+
def generate_test_description():
51+
launch_include = IncludeLaunchDescription(
52+
PythonLaunchDescriptionSource(
53+
os.path.join(
54+
get_package_share_directory("ros2_control_demo_example_1"),
55+
"launch/rrbot.launch.py",
56+
)
57+
),
58+
launch_arguments={"gui": "False"}.items(),
59+
)
60+
61+
return LaunchDescription([launch_include, ReadyToTest()])
62+
63+
64+
class TestFixtureCliDirect(unittest.TestCase):
65+
66+
def setUp(self):
67+
rclpy.init()
68+
self.node = Node("test_node")
69+
70+
def tearDown(self):
71+
self.node.destroy_node()
72+
rclpy.shutdown()
73+
74+
def test_main(self, proc_output):
75+
76+
# Command to run the CLI
77+
cname = "joint_trajectory_position_controller"
78+
command = [
79+
"ros2",
80+
"control",
81+
"load_controller",
82+
"--set-state",
83+
"inactive",
84+
cname,
85+
os.path.join(
86+
get_package_share_directory("ros2_control_demo_example_1"),
87+
"config/rrbot_jtc.yaml",
88+
),
89+
]
90+
subprocess.run(command, check=True)
91+
check_controllers_running(self.node, [cname], state="inactive")
92+
check_controllers_running(self.node, ["forward_position_controller"], state="active")
93+
94+
command = [
95+
"ros2",
96+
"control",
97+
"switch_controllers",
98+
"--activate",
99+
cname,
100+
"--deactivate",
101+
"forward_position_controller",
102+
]
103+
subprocess.run(command, check=True)
104+
check_controllers_running(self.node, ["forward_position_controller"], state="inactive")
105+
check_controllers_running(self.node, [cname], state="active")
106+
107+
108+
# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
109+
# @launch_testing.post_shutdown_test()
110+
# # These tests are run after the processes in generate_test_description() have shutdown.
111+
# class TestDescriptionCraneShutdown(unittest.TestCase):
112+
113+
# def test_exit_codes(self, proc_info):
114+
# """Check if the processes exited normally."""
115+
# launch_testing.asserts.assertExitCodes(proc_info)

ros2_control_demo_testing/ros2_control_demo_testing/test_utils.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ def check_node_running(node, node_name, timeout=5.0):
4545
assert found, f"{node_name} not found!"
4646

4747

48-
def check_controllers_running(node, cnames, namespace=""):
48+
def check_controllers_running(node, cnames, namespace="", state="active"):
4949

5050
# wait for controller to be loaded before we call the CM services
5151
found = {cname: False for cname in cnames} # Define 'found' as a dictionary
@@ -85,14 +85,14 @@ def check_controllers_running(node, cnames, namespace=""):
8585
assert controllers, "No controllers found!"
8686
for c in controllers:
8787
for cname in cnames:
88-
if c.name == cname and c.state == "active":
88+
if c.name == cname and c.state == state:
8989
found[cname] = True
9090
break
9191
time.sleep(0.1)
9292

9393
assert all(
9494
found.values()
95-
), f"Controller(s) not found or not active: {', '.join([cname for cname, is_found in found.items() if not is_found])}"
95+
), f"Controller(s) not found or not {state}: {', '.join([cname for cname, is_found in found.items() if not is_found])}"
9696

9797

9898
def check_if_js_published(topic, joint_names):

0 commit comments

Comments
 (0)