Skip to content

Commit bc23c01

Browse files
authored
Add Trajectory Cache Example For Refactor (#940)
Signed-off-by: methylDragon <[email protected]>
1 parent 3e6de33 commit bc23c01

23 files changed

+2355
-0
lines changed

CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1919
moveit_msgs
2020
moveit_ros_planning
2121
moveit_ros_planning_interface
22+
moveit_ros_trajectory_cache
2223
moveit_servo
2324
moveit_task_constructor_core
2425
moveit_visual_tools
@@ -29,6 +30,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
2930
tf2_geometry_msgs
3031
tf2_geometry_msgs
3132
tf2_ros
33+
warehouse_ros_sqlite
3234
)
3335

3436
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
@@ -69,6 +71,7 @@ add_subdirectory(doc/how_to_guides/parallel_planning)
6971
add_subdirectory(doc/how_to_guides/chomp_planner)
7072
add_subdirectory(doc/how_to_guides/persistent_scenes_and_states)
7173
add_subdirectory(doc/how_to_guides/pilz_industrial_motion_planner)
74+
add_subdirectory(doc/how_to_guides/trajectory_cache)
7275
add_subdirectory(doc/how_to_guides/using_ompl_constrained_planning)
7376
add_subdirectory(doc/tutorials/pick_and_place_with_moveit_task_constructor)
7477
add_subdirectory(doc/tutorials/quickstart_in_rviz)
1.25 MB
Binary file not shown.
4.28 MB
Binary file not shown.

doc/how_to_guides/how_to_guides.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@ Configuring and Using MoveIt
2525
pick_ik/pick_ik_tutorial
2626
trac_ik/trac_ik_tutorial
2727
benchmarking/benchmarking_tutorial
28+
trajectory_cache/trajectory_cache_tutorial
2829

2930
Developing and Documenting MoveIt
3031
---------------------------------
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
add_executable(trajectory_cache_demo src/trajectory_cache_demo.cpp)
2+
ament_target_dependencies(trajectory_cache_demo ${THIS_PACKAGE_INCLUDE_DEPENDS} Boost moveit_ros_trajectory_cache)
3+
4+
install(TARGETS trajectory_cache_demo DESTINATION lib/${PROJECT_NAME})
5+
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
6+
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
# These are faster joint limits to allow for faster execution.
2+
joint_limits:
3+
panda_joint1:
4+
has_velocity_limits: true
5+
max_velocity: 50.0
6+
has_acceleration_limits: true
7+
max_acceleration: 5.0
8+
has_jerk_limits: false
9+
panda_joint2:
10+
has_velocity_limits: true
11+
max_velocity: 50.0
12+
has_acceleration_limits: true
13+
max_acceleration: 5.0
14+
has_jerk_limits: false
15+
panda_joint3:
16+
has_velocity_limits: true
17+
max_velocity: 50.0
18+
has_acceleration_limits: true
19+
max_acceleration: 5.0
20+
has_jerk_limits: false
21+
panda_joint4:
22+
has_velocity_limits: true
23+
max_velocity: 50.0
24+
has_acceleration_limits: true
25+
max_acceleration: 5.0
26+
has_jerk_limits: false
27+
panda_joint5:
28+
has_velocity_limits: true
29+
max_velocity: 50.0
30+
has_acceleration_limits: true
31+
max_acceleration: 5.0
32+
has_jerk_limits: false
33+
panda_joint6:
34+
has_velocity_limits: true
35+
max_velocity: 50.0
36+
has_acceleration_limits: true
37+
max_acceleration: 5.0
38+
has_jerk_limits: false
39+
panda_joint7:
40+
has_velocity_limits: true
41+
max_velocity: 50.0
42+
has_acceleration_limits: true
43+
max_acceleration: 5.0
44+
has_jerk_limits: false
45+
panda_finger_joint1:
46+
has_velocity_limits: true
47+
max_velocity: 25.0
48+
has_acceleration_limits: true
49+
max_acceleration: 5.0
50+
has_jerk_limits: false
51+
panda_finger_joint2:
52+
has_velocity_limits: true
53+
max_velocity: 25.0
54+
has_acceleration_limits: true
55+
max_acceleration: 5.0
56+
has_jerk_limits: false
219 KB
Loading
369 KB
Loading
67.9 KB
Loading
233 KB
Loading

0 commit comments

Comments
 (0)