Skip to content

Commit 4c2971d

Browse files
Felix Exner (fexner)mrjogoVinDp
authored
Make moveit_config compatible to moveit_configs_builder (#998)
* Make the config moveit_configs_builder compatible - Make sure it can be used in conjunction with the configs builder - Still use a parametrized srdf - Re-use the description from the robot state publisher * Wait for robot_description in moveit startup Since we built our moveit config around receiving the description via topic, we also add a script that waits for the robot description to be published. This helps when components support subscribing to the description, but crash if it is not present. * Added servo node * Add servo node config to disable advertising /get_planning_scene * Apply suggestions from code review Co-authored-by: Vincenzo Di Pentima <[email protected]> * Fix corrections * Added missing dependency for chomp planners * Added use_sim_time argument and defaulted launch_servo to false * Launchfile formatting --------- Co-authored-by: Ruddick Lawrence <[email protected]> Co-authored-by: Vincenzo Di Pentima <[email protected]>
1 parent 9da8109 commit 4c2971d

18 files changed

+343
-569
lines changed

ur_moveit_config/CMakeLists.txt

Lines changed: 5 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,11 @@
1-
cmake_minimum_required(VERSION 3.5)
1+
cmake_minimum_required(VERSION 3.22)
22
project(ur_moveit_config)
33

44
find_package(ament_cmake REQUIRED)
5-
find_package(ament_cmake_python REQUIRED)
65

7-
install(DIRECTORY config launch rviz srdf
6+
ament_package()
7+
8+
install(
9+
DIRECTORY config launch
810
DESTINATION share/${PROJECT_NAME}
911
)
10-
11-
# Install Python modules
12-
ament_python_install_package(${PROJECT_NAME})
13-
ament_python_install_module(${PROJECT_NAME}/launch_common.py)
14-
15-
ament_package()
Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
planning_plugins:
2+
- chomp_interface/CHOMPPlanner
3+
enable_failure_recovery: true
4+
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
5+
request_adapters:
6+
- default_planning_request_adapters/ResolveConstraintFrames
7+
- default_planning_request_adapters/ValidateWorkspaceBounds
8+
- default_planning_request_adapters/CheckStartStateBounds
9+
- default_planning_request_adapters/CheckStartStateCollision
10+
response_adapters:
11+
- default_planning_response_adapters/AddTimeOptimalParameterization
12+
- default_planning_response_adapters/ValidateSolution
13+
- default_planning_response_adapters/DisplayMotionPath
14+
15+
ridge_factor: 0.01

ur_moveit_config/config/controllers.yaml

Lines changed: 0 additions & 29 deletions
This file was deleted.
Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,4 @@
1-
/**:
2-
ros__parameters:
3-
robot_description_kinematics:
4-
ur_manipulator:
5-
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
6-
kinematics_solver_search_resolution: 0.005
7-
kinematics_solver_timeout: 0.005
8-
kinematics_solver_attempts: 3
1+
ur_manipulator:
2+
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
3+
kinematics_solver_search_resolution: 0.0050000000000000001
4+
kinematics_solver_timeout: 0.0050000000000000001
File renamed without changes.
Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
# MoveIt uses this configuration for controller management
2+
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
3+
4+
moveit_simple_controller_manager:
5+
controller_names:
6+
- scaled_joint_trajectory_controller
7+
- joint_trajectory_controller
8+
9+
scaled_joint_trajectory_controller:
10+
action_ns: follow_joint_trajectory
11+
type: FollowJointTrajectory
12+
default: true
13+
joints:
14+
- shoulder_pan_joint
15+
- shoulder_lift_joint
16+
- elbow_joint
17+
- wrist_1_joint
18+
- wrist_2_joint
19+
- wrist_3_joint
20+
21+
22+
joint_trajectory_controller:
23+
action_ns: follow_joint_trajectory
24+
type: FollowJointTrajectory
25+
default: false
26+
joints:
27+
- shoulder_pan_joint
28+
- shoulder_lift_joint
29+
- elbow_joint
30+
- wrist_1_joint
31+
- wrist_2_joint
32+
- wrist_3_joint
Lines changed: 12 additions & 70 deletions
Original file line numberDiff line numberDiff line change
@@ -1,70 +1,12 @@
1-
planner_configs:
2-
SBLkConfigDefault:
3-
type: geometric::SBL
4-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
5-
ESTkConfigDefault:
6-
type: geometric::EST
7-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
8-
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
9-
LBKPIECEkConfigDefault:
10-
type: geometric::LBKPIECE
11-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
12-
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
13-
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
14-
BKPIECEkConfigDefault:
15-
type: geometric::BKPIECE
16-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
17-
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
18-
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
19-
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
20-
KPIECEkConfigDefault:
21-
type: geometric::KPIECE
22-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
23-
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
24-
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
25-
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
26-
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
27-
RRTkConfigDefault:
28-
type: geometric::RRT
29-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
30-
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
31-
RRTConnectkConfigDefault:
32-
type: geometric::RRTConnect
33-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
34-
RRTstarkConfigDefault:
35-
type: geometric::RRTstar
36-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
37-
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
38-
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
39-
TRRTkConfigDefault:
40-
type: geometric::TRRT
41-
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
42-
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
43-
max_states_failed: 10 # when to start increasing temp. default: 10
44-
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
45-
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
46-
init_temperature: 10e-6 # initial temperature. default: 10e-6
47-
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
48-
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
49-
k_constant: 0.0 # value used to normalize expression. default: 0.0 set in setup()
50-
PRMkConfigDefault:
51-
type: geometric::PRM
52-
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
53-
PRMstarkConfigDefault:
54-
type: geometric::PRMstar
55-
ur_manipulator:
56-
planner_configs:
57-
- SBLkConfigDefault
58-
- ESTkConfigDefault
59-
- LBKPIECEkConfigDefault
60-
- BKPIECEkConfigDefault
61-
- KPIECEkConfigDefault
62-
- RRTkConfigDefault
63-
- RRTConnectkConfigDefault
64-
- RRTstarkConfigDefault
65-
- TRRTkConfigDefault
66-
- PRMkConfigDefault
67-
- PRMstarkConfigDefault
68-
##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE
69-
#projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)
70-
longest_valid_segment_fraction: 0.01
1+
planning_plugins:
2+
- ompl_interface/OMPLPlanner
3+
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
4+
request_adapters:
5+
- default_planning_request_adapters/ResolveConstraintFrames
6+
- default_planning_request_adapters/ValidateWorkspaceBounds
7+
- default_planning_request_adapters/CheckStartStateBounds
8+
- default_planning_request_adapters/CheckStartStateCollision
9+
response_adapters:
10+
- default_planning_response_adapters/AddTimeOptimalParameterization
11+
- default_planning_response_adapters/ValidateSolution
12+
- default_planning_response_adapters/DisplayMotionPath
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
# Limits for the Pilz planner
2+
cartesian_limits:
3+
max_trans_vel: 1.0
4+
max_trans_acc: 2.25
5+
max_trans_dec: -5.0
6+
max_rot_vel: 1.57
Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
planning_plugins:
2+
- pilz_industrial_motion_planner/CommandPlanner
3+
default_planner_config: PTP
4+
request_adapters:
5+
- default_planning_request_adapters/ResolveConstraintFrames
6+
- default_planning_request_adapters/ValidateWorkspaceBounds
7+
- default_planning_request_adapters/CheckStartStateBounds
8+
- default_planning_request_adapters/CheckStartStateCollision
9+
response_adapters:
10+
- default_planning_response_adapters/ValidateSolution
11+
- default_planning_response_adapters/DisplayMotionPath
12+
capabilities: >-
13+
pilz_industrial_motion_planner/MoveGroupSequenceAction
14+
pilz_industrial_motion_planner/MoveGroupSequenceService

ur_moveit_config/config/ur_servo.yaml

Lines changed: 30 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,11 @@
44
use_gazebo: false # Whether the robot is started in a Gazebo simulation environment
55

66
## Properties of incoming commands
7-
command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s
7+
command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s
88
scale:
99
# Scale parameters are only used if command_in_type=="unitless"
10-
linear: 0.6 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands.
11-
rotational: 0.3 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands.
10+
linear: 0.6 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands.
11+
rotational: 0.3 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands.
1212
# Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic.
1313
joint: 0.01
1414
# This is a fudge factor to account for any latency in the system, e.g. network latency or poor low-level
@@ -32,45 +32,54 @@ publish_joint_accelerations: false
3232
## Plugins for smoothing outgoing commands
3333
smoothing_filter_plugin_name: "online_signal_smoothing::ButterworthFilterPlugin"
3434

35+
# If is_primary_planning_scene_monitor is set to true, the Servo server's PlanningScene advertises the /get_planning_scene service,
36+
# which other nodes can use as a source for information about the planning environment.
37+
# NOTE: If a different node in your system is responsible for the "primary" planning scene instance (e.g. the MoveGroup node),
38+
# then is_primary_planning_scene_monitor needs to be set to false.
39+
is_primary_planning_scene_monitor: false
40+
3541
## Incoming Joint State properties
3642
low_pass_filter_coeff: 10.0 # Larger --> trust the filtered data more, trust the measurements less.
3743

3844
## MoveIt properties
39-
move_group_name: ur_manipulator # Often 'manipulator' or 'arm'
45+
move_group_name: ur_manipulator # Often 'manipulator' or 'arm'
4046
planning_frame: base_link # The MoveIt planning frame. Often 'base_link' or 'world'
4147

4248
## Other frames
4349
ee_frame: tool0 # The name of the end effector link, used to return the EE pose
44-
robot_link_command_frame: tool0 # commands must be given in the frame of a robot link. Usually either the base or end effector
50+
robot_link_command_frame: tool0 # commands must be given in the frame of a robot link. Usually either the base or end effector
4551

4652
## Stopping behaviour
47-
incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command
53+
incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command
4854
# If 0, republish commands forever even if the robot is stationary. Otherwise, specify num. to publish.
4955
# Important because ROS may drop some messages and we need the robot to halt reliably.
5056
num_outgoing_halt_msgs_to_publish: 4
5157

5258
## Configure handling of singularities and joint limits
53-
lower_singularity_threshold: 100.0 # Start decelerating when the condition number hits this (close to singularity)
54-
hard_stop_singularity_threshold: 200.0 # Stop when the condition number hits this
55-
joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger.
59+
lower_singularity_threshold: 100.0 # Start decelerating when the condition number hits this (close to singularity)
60+
hard_stop_singularity_threshold: 200.0 # Stop when the condition number hits this
61+
62+
# added as a buffer to joint limits [radians]. If moving quickly, make this larger.
63+
joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1]
5664

5765
## Topic names
5866
cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands
59-
joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands
67+
joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands
6068
joint_topic: /joint_states
61-
status_topic: ~/status # Publish status to this topic
62-
command_out_topic: /forward_position_controller/commands # Publish outgoing commands here
69+
status_topic: ~/status # Publish status to this topic
70+
command_out_topic: /forward_position_controller/commands # Publish outgoing commands here
6371

6472
## Collision checking for the entire robot body
65-
check_collisions: true # Check collisions?
66-
collision_check_rate: 5.0 # [Hz] Collision-checking can easily bog down a CPU if done too often.
67-
# Two collision check algorithms are available:
68-
# "threshold_distance" begins slowing down when nearer than a specified distance. Good if you want to tune collision thresholds manually.
69-
# "stop_distance" stops if a collision is nearer than the worst-case stopping distance and the distance is decreasing. Requires joint acceleration limits
73+
check_collisions: true # Check collisions?
74+
collision_check_rate: 5.0 # [Hz] Collision-checking can easily bog down a CPU if done too often.
75+
# Two collision check algorithms are available: "threshold_distance" begins slowing down when
76+
# nearer than a specified distance. Good if you want to tune collision thresholds manually.
77+
# "stop_distance" stops if a collision is nearer than the worst-case stopping distance and the
78+
# distance is decreasing. Requires joint acceleration limits
7079
collision_check_type: threshold_distance
7180
# Parameters for "threshold_distance"-type collision checking
72-
self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m]
73-
scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m]
81+
self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m]
82+
scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m]
7483
# Parameters for "stop_distance"-type collision checking
75-
collision_distance_safety_factor: 1000.0 # Must be >= 1. A large safety factor is recommended to account for latency
76-
min_allowable_collision_distance: 0.01 # Stop if a collision is closer than this [m]
84+
collision_distance_safety_factor: 1000.0 # Must be >= 1. A large safety factor is recommended to account for latency
85+
min_allowable_collision_distance: 0.01 # Stop if a collision is closer than this [m]

0 commit comments

Comments
 (0)