Skip to content

Commit aa77650

Browse files
committed
Refactor tutorial to support TrajectoryCache refactor
Signed-off-by: methylDragon <[email protected]>
1 parent 935b7a9 commit aa77650

File tree

5 files changed

+162
-128
lines changed

5 files changed

+162
-128
lines changed

doc/how_to_guides/trajectory_cache/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,4 +3,4 @@ ament_target_dependencies(trajectory_cache_demo ${THIS_PACKAGE_INCLUDE_DEPENDS}
33

44
install(TARGETS trajectory_cache_demo DESTINATION lib/${PROJECT_NAME})
55
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
6-
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
6+
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})

doc/how_to_guides/trajectory_cache/config/trajectory_cache_joint_limits.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,4 +53,4 @@ joint_limits:
5353
max_velocity: 25.0
5454
has_acceleration_limits: true
5555
max_acceleration: 5.0
56-
has_jerk_limits: false
56+
has_jerk_limits: false

doc/how_to_guides/trajectory_cache/launch/trajectory_cache_demo.launch.py

Lines changed: 45 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -20,81 +20,77 @@
2020

2121
configurable_parameters = {
2222
# Cache DB
23-
'cache_db_plugin': {
24-
'default': 'warehouse_ros_sqlite::DatabaseConnection',
25-
'description': 'Plugin to use for the trajectory cache database.'
23+
"cache_db_plugin": {
24+
"default": "warehouse_ros_sqlite::DatabaseConnection",
25+
"description": "Plugin to use for the trajectory cache database.",
2626
},
27-
'cache_db_host': {
28-
'default': '":memory:"',
29-
'description': 'Host for the trajectory cache database. Use ":memory:" for an in-memory database.'
27+
"cache_db_host": {
28+
"default": '":memory:"',
29+
"description": 'Host for the trajectory cache database. Use ":memory:" for an in-memory database.',
3030
},
31-
'cache_db_port': {
32-
'default': '0',
33-
'description': 'Port for the trajectory cache database.'
31+
"cache_db_port": {
32+
"default": "0",
33+
"description": "Port for the trajectory cache database.",
3434
},
35-
3635
# Reconfigurable (these can be set at runtime and will update)
37-
'start_tolerance': { # Trajectory cache param
38-
'default': '0.025',
39-
'description': 'Reconfigurable cache param. Tolerance for the start state of the trajectory.'
36+
"start_tolerance": { # Trajectory cache param
37+
"default": "0.025",
38+
"description": "Reconfigurable cache param. Tolerance for the start state of the trajectory.",
4039
},
41-
'goal_tolerance': { # Trajectory cache param
42-
'default': '0.001',
43-
'description': 'Reconfigurable cache param. Tolerance for the goal state of the trajectory.'
40+
"goal_tolerance": { # Trajectory cache param
41+
"default": "0.001",
42+
"description": "Reconfigurable cache param. Tolerance for the goal state of the trajectory.",
4443
},
45-
'prune_worse_trajectories': { # Trajectory cache param
46-
'default': 'false',
47-
'description': 'Reconfigurable cache param. Whether to delete trajectories that are worse than the current trajectory.'
44+
"prune_worse_trajectories": { # Trajectory cache param
45+
"default": "false",
46+
"description": "Reconfigurable cache param. Whether to delete trajectories that are worse than the current trajectory.",
4847
},
49-
'planner': {
50-
'default': 'RRTstar',
51-
'description': 'Reconfigurable. Planner to use for trajectory planning.'
48+
"planner": {
49+
"default": "RRTstar",
50+
"description": "Reconfigurable. Planner to use for trajectory planning.",
5251
},
53-
5452
# Tutorial
55-
'num_target_poses': {
56-
'default': '4',
57-
'description': 'Number of target poses to generate.'
53+
"num_target_poses": {
54+
"default": "4",
55+
"description": "Number of target poses to generate.",
5856
},
59-
'num_cartesian_target_paths_per_target_pose': {
60-
'default': '2', 'description': 'Number of Cartesian paths to generate for each target pose.'
57+
"num_cartesian_target_paths_per_target_pose": {
58+
"default": "2",
59+
"description": "Number of Cartesian paths to generate for each target pose.",
6160
},
62-
'cartesian_path_distance_m': {
63-
'default': '0.10',
64-
'description': 'Length of the Cartesian path to set the goal for.'
61+
"cartesian_path_distance_m": {
62+
"default": "0.10",
63+
"description": "Length of the Cartesian path to set the goal for.",
6564
},
66-
6765
# Trajectory Cache
68-
'exact_match_precision': {
66+
"exact_match_precision": {
6967
# Purposely set a relatively high value to make pruning obvious.
70-
'default': '0.0001',
71-
'description': 'Precision for checking if two trajectories are exactly the same.'
68+
"default": "0.0001",
69+
"description": "Precision for checking if two trajectories are exactly the same.",
7270
},
73-
'cartesian_max_step': {
74-
'default': '0.001',
75-
'description': 'Maximum step size for the Cartesian path.'
71+
"cartesian_max_step": {
72+
"default": "0.001",
73+
"description": "Maximum step size for the Cartesian path.",
7674
},
77-
'cartesian_jump_threshold': {
78-
'default': '0.0',
79-
'description': 'Threshold for the jump distance between points in the Cartesian path.'
75+
"cartesian_jump_threshold": {
76+
"default": "0.0",
77+
"description": "Threshold for the jump distance between points in the Cartesian path.",
8078
},
8179
}
8280

8381

8482
def declare_configurable_parameters(parameters):
8583
return [
8684
DeclareLaunchArgument(
87-
param_name,
88-
default_value=param['default'],
89-
description=param['description']
90-
) for param_name, param in parameters.items()
85+
param_name, default_value=param["default"], description=param["description"]
86+
)
87+
for param_name, param in parameters.items()
9188
]
9289

9390

9491
def set_configurable_parameters(parameters):
9592
return {
96-
param_name: LaunchConfiguration(param_name)
97-
for param_name in parameters.keys()
93+
param_name: LaunchConfiguration(param_name) for param_name in parameters.keys()
9894
}
9995

10096

@@ -114,8 +110,6 @@ def generate_launch_description():
114110
)
115111

116112
return LaunchDescription(
117-
declare_configurable_parameters(configurable_parameters) +
118-
[
119-
trajectory_cache_demo
120-
]
113+
declare_configurable_parameters(configurable_parameters)
114+
+ [trajectory_cache_demo]
121115
)

doc/how_to_guides/trajectory_cache/launch/trajectory_cache_move_group.launch.py

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,9 @@
33
from ament_index_python.packages import get_package_share_directory
44

55
from launch import LaunchDescription
6-
from launch.actions import DeclareLaunchArgument, ExecuteProcess
7-
from launch.substitutions import LaunchConfiguration, TextSubstitution
8-
6+
from launch.actions import ExecuteProcess, TimerAction
97
from launch_ros.actions import Node
8+
109
from moveit_configs_utils import MoveItConfigsBuilder
1110

1211
joint_limits_path = os.path.join(
@@ -36,8 +35,8 @@ def generate_launch_description():
3635

3736
# RViz
3837
rviz_config_file = (
39-
get_package_share_directory(
40-
"moveit2_tutorials") + "/launch/trajectory_cache.rviz"
38+
get_package_share_directory("moveit2_tutorials")
39+
+ "/launch/trajectory_cache.rviz"
4140
)
4241
rviz_node = Node(
4342
package="rviz2",
@@ -97,8 +96,7 @@ def generate_launch_description():
9796
]:
9897
load_controllers += [
9998
ExecuteProcess(
100-
cmd=["ros2 run controller_manager spawner {}".format(
101-
controller)],
99+
cmd=["ros2 run controller_manager spawner {}".format(controller)],
102100
shell=True,
103101
output="screen",
104102
)
@@ -109,8 +107,8 @@ def generate_launch_description():
109107
rviz_node,
110108
static_tf,
111109
robot_state_publisher,
112-
run_move_group_node,
113110
ros2_control_node,
111+
TimerAction(period=2.0, actions=[run_move_group_node]),
114112
]
115113
+ load_controllers
116114
)

0 commit comments

Comments
 (0)