Skip to content

Make check_starting_point of test_move launch files configurable #1354

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

Merged
merged 1 commit into from
May 6, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 0 additions & 2 deletions ur_robot_driver/config/test_goal_publishers_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@ publisher_scaled_joint_trajectory_controller:
- wrist_2_joint
- wrist_3_joint

check_starting_point: true
starting_point_limits:
shoulder_pan_joint: [-0.1,0.1]
shoulder_lift_joint: [-1.6,-1.5]
Expand Down Expand Up @@ -55,7 +54,6 @@ publisher_joint_trajectory_controller:
- wrist_2_joint
- wrist_3_joint

check_starting_point: true
starting_point_limits:
shoulder_pan_joint: [-0.1,0.1]
shoulder_lift_joint: [-1.6,-1.5]
Expand Down
15 changes: 15 additions & 0 deletions ur_robot_driver/doc/usage/move.rst
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,21 @@ First check the controllers' state using ``ros2 control list_controllers``, befo

The robot should move, after a few seconds.

.. note::
By default, the robot's pose is checked for being close to a predefined configuration in order
to make sure that the robot doesn't perform any large, unexpected motions. This configuration
is specified in the ``config/test_goal_publishers.yaml`` config file of the
``ur_robot_driver`` package. The joint values are

.. code-block:: yaml

shoulder_pan_joint: 0
shoulder_lift_joint: -1.57
elbow_joint: 0
wrist_1_joint: -1.57
wrist_2_joint: 0
wrist_3_joint: 0

* To test another controller, simply define it using ``initial_joint_controller`` argument, for example when using mock hardware:

.. code-block:: console
Expand Down
25 changes: 21 additions & 4 deletions ur_robot_driver/launch/test_joint_trajectory_controller.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,24 +32,41 @@
# Description: After a robot has been loaded, this will execute a series of trajectories.

from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
position_goals = PathJoinSubstitution(
[FindPackageShare("ur_robot_driver"), "config", "test_goal_publishers_config.yaml"]
[
FindPackageShare("ur_robot_driver"),
"config",
"test_goal_publishers_config.yaml",
]
)

check_starting_point = LaunchConfiguration("check_starting_point")

return LaunchDescription(
[
DeclareLaunchArgument(
"check_starting_point",
default_value="true",
description="Verify that the robot is at a preconfigured pose in order to avoid large unexpected motions.",
),
Node(
package="ros2_controllers_test_nodes",
executable="publisher_joint_trajectory_controller",
name="publisher_joint_trajectory_controller",
parameters=[position_goals],
parameters=[
position_goals,
{
"check_starting_point": check_starting_point,
},
],
output="screen",
)
),
]
)
Original file line number Diff line number Diff line change
Expand Up @@ -32,24 +32,41 @@
# Description: After a robot has been loaded, this will execute a series of trajectories.

from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
position_goals = PathJoinSubstitution(
[FindPackageShare("ur_robot_driver"), "config", "test_goal_publishers_config.yaml"]
[
FindPackageShare("ur_robot_driver"),
"config",
"test_goal_publishers_config.yaml",
]
)

check_starting_point = LaunchConfiguration("check_starting_point")

return LaunchDescription(
[
DeclareLaunchArgument(
"check_starting_point",
default_value="true",
description="Verify that the robot is at a preconfigured pose in order to avoid large unexpected motions.",
),
Node(
package="ros2_controllers_test_nodes",
executable="publisher_joint_trajectory_controller",
name="publisher_scaled_joint_trajectory_controller",
parameters=[position_goals],
parameters=[
position_goals,
{
"check_starting_point": check_starting_point,
},
],
output="screen",
)
),
]
)
Loading