Skip to content

Commit 7bc1ddb

Browse files
committed
Make check_starting_point of test_move launch files configurable
This should allow to use them in situations, where the robot is not at the preconfigured pose, but users understand the risks and want to circumvent this. Also, I updated the documentation around this.
1 parent 81f71bc commit 7bc1ddb

File tree

4 files changed

+57
-10
lines changed

4 files changed

+57
-10
lines changed

ur_robot_driver/config/test_goal_publishers_config.yaml

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@ publisher_scaled_joint_trajectory_controller:
2222
- wrist_2_joint
2323
- wrist_3_joint
2424

25-
check_starting_point: true
2625
starting_point_limits:
2726
shoulder_pan_joint: [-0.1,0.1]
2827
shoulder_lift_joint: [-1.6,-1.5]
@@ -55,7 +54,6 @@ publisher_joint_trajectory_controller:
5554
- wrist_2_joint
5655
- wrist_3_joint
5756

58-
check_starting_point: true
5957
starting_point_limits:
6058
shoulder_pan_joint: [-0.1,0.1]
6159
shoulder_lift_joint: [-1.6,-1.5]

ur_robot_driver/doc/usage/move.rst

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,21 @@ First check the controllers' state using ``ros2 control list_controllers``, befo
1616
1717
The robot should move, after a few seconds.
1818

19+
.. note::
20+
By default, the robot's pose is checked for being close to a predefined configuration in order
21+
to make sure that the robot doesn't perform any large, unexpected motions. This configuration
22+
is specified in the ``config/test_goal_publishers.yaml`` config file of the
23+
``ur_robot_driver`` package. The joint values are
24+
25+
.. code-block:: yaml
26+
27+
shoulder_pan_joint: 0
28+
shoulder_lift_joint: -1.57
29+
elbow_joint: 0
30+
wrist_1_joint: -1.57
31+
wrist_2_joint: 0
32+
wrist_3_joint: 0
33+
1934
* To test another controller, simply define it using ``initial_joint_controller`` argument, for example when using mock hardware:
2035

2136
.. code-block:: console

ur_robot_driver/launch/test_joint_trajectory_controller.launch.py

Lines changed: 21 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,24 +32,41 @@
3232
# Description: After a robot has been loaded, this will execute a series of trajectories.
3333

3434
from launch import LaunchDescription
35-
from launch.substitutions import PathJoinSubstitution
35+
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
36+
from launch.actions import DeclareLaunchArgument
3637
from launch_ros.actions import Node
3738
from launch_ros.substitutions import FindPackageShare
3839

3940

4041
def generate_launch_description():
4142
position_goals = PathJoinSubstitution(
42-
[FindPackageShare("ur_robot_driver"), "config", "test_goal_publishers_config.yaml"]
43+
[
44+
FindPackageShare("ur_robot_driver"),
45+
"config",
46+
"test_goal_publishers_config.yaml",
47+
]
4348
)
4449

50+
check_starting_point = LaunchConfiguration("check_starting_point")
51+
4552
return LaunchDescription(
4653
[
54+
DeclareLaunchArgument(
55+
"check_starting_point",
56+
default_value="true",
57+
description="Verify that the robot is at a preconfigured pose in order to avoid large unexpected motions.",
58+
),
4759
Node(
4860
package="ros2_controllers_test_nodes",
4961
executable="publisher_joint_trajectory_controller",
5062
name="publisher_joint_trajectory_controller",
51-
parameters=[position_goals],
63+
parameters=[
64+
position_goals,
65+
{
66+
"check_starting_point": check_starting_point,
67+
},
68+
],
5269
output="screen",
53-
)
70+
),
5471
]
5572
)

ur_robot_driver/launch/test_scaled_joint_trajectory_controller.launch.py

Lines changed: 21 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,24 +32,41 @@
3232
# Description: After a robot has been loaded, this will execute a series of trajectories.
3333

3434
from launch import LaunchDescription
35-
from launch.substitutions import PathJoinSubstitution
35+
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
36+
from launch.actions import DeclareLaunchArgument
3637
from launch_ros.actions import Node
3738
from launch_ros.substitutions import FindPackageShare
3839

3940

4041
def generate_launch_description():
4142
position_goals = PathJoinSubstitution(
42-
[FindPackageShare("ur_robot_driver"), "config", "test_goal_publishers_config.yaml"]
43+
[
44+
FindPackageShare("ur_robot_driver"),
45+
"config",
46+
"test_goal_publishers_config.yaml",
47+
]
4348
)
4449

50+
check_starting_point = LaunchConfiguration("check_starting_point")
51+
4552
return LaunchDescription(
4653
[
54+
DeclareLaunchArgument(
55+
"check_starting_point",
56+
default_value="true",
57+
description="Verify that the robot is at a preconfigured pose in order to avoid large unexpected motions.",
58+
),
4759
Node(
4860
package="ros2_controllers_test_nodes",
4961
executable="publisher_joint_trajectory_controller",
5062
name="publisher_scaled_joint_trajectory_controller",
51-
parameters=[position_goals],
63+
parameters=[
64+
position_goals,
65+
{
66+
"check_starting_point": check_starting_point,
67+
},
68+
],
5269
output="screen",
53-
)
70+
),
5471
]
5572
)

0 commit comments

Comments
 (0)