Skip to content

Commit c8d961e

Browse files
Define default maximum accelerations for MoveIt (backport of #645) (#981)
(cherry picked from commit 5e3c464) Co-authored-by: RobertWilbrandt <[email protected]>
1 parent 69dbd41 commit c8d961e

File tree

2 files changed

+46
-10
lines changed

2 files changed

+46
-10
lines changed
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# These limits are used by MoveIt and augment/override the definitions in ur_description.
2+
#
3+
# While the robot does not inherently have any limits on joint accelerations (only on torques),
4+
# MoveIt needs them for time parametrization. They were chosen conservatively to work in most use
5+
# cases. For specific applications, higher values might lead to better execution performance.
6+
7+
joint_limits:
8+
shoulder_pan_joint:
9+
has_acceleration_limits: true
10+
max_acceleration: 5.0
11+
shoulder_lift_joint:
12+
has_acceleration_limits: true
13+
max_acceleration: 5.0
14+
elbow_joint:
15+
has_acceleration_limits: true
16+
max_acceleration: 5.0
17+
wrist_1_joint:
18+
has_acceleration_limits: true
19+
max_acceleration: 5.0
20+
wrist_2_joint:
21+
has_acceleration_limits: true
22+
max_acceleration: 5.0
23+
wrist_3_joint:
24+
has_acceleration_limits: true
25+
max_acceleration: 5.0

ur_moveit_config/launch/ur_moveit.launch.py

Lines changed: 21 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -31,15 +31,15 @@
3131

3232
import os
3333

34-
from launch import LaunchDescription
35-
from launch.actions import DeclareLaunchArgument
36-
from launch.actions import OpaqueFunction
37-
from launch.conditions import IfCondition
38-
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
3934
from launch_ros.actions import Node
4035
from launch_ros.substitutions import FindPackageShare
4136
from ur_moveit_config.launch_common import load_yaml
4237

38+
from launch import LaunchDescription
39+
from launch.actions import DeclareLaunchArgument, OpaqueFunction
40+
from launch.conditions import IfCondition
41+
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
42+
4343

4444
def launch_setup(context, *args, **kwargs):
4545

@@ -53,6 +53,7 @@ def launch_setup(context, *args, **kwargs):
5353
description_package = LaunchConfiguration("description_package")
5454
description_file = LaunchConfiguration("description_file")
5555
moveit_config_package = LaunchConfiguration("moveit_config_package")
56+
moveit_joint_limits_file = LaunchConfiguration("moveit_joint_limits_file")
5657
moveit_config_file = LaunchConfiguration("moveit_config_file")
5758
warehouse_sqlite_path = LaunchConfiguration("warehouse_sqlite_path")
5859
prefix = LaunchConfiguration("prefix")
@@ -146,9 +147,12 @@ def launch_setup(context, *args, **kwargs):
146147
[FindPackageShare(moveit_config_package), "config", "kinematics.yaml"]
147148
)
148149

149-
# robot_description_planning = {
150-
# "robot_description_planning": load_yaml_abs(str(joint_limit_params.perform(context)))
151-
# }
150+
robot_description_planning = {
151+
"robot_description_planning": load_yaml(
152+
str(moveit_config_package.perform(context)),
153+
os.path.join("config", str(moveit_joint_limits_file.perform(context))),
154+
)
155+
}
152156

153157
# Planning Configuration
154158
ompl_planning_pipeline_config = {
@@ -202,7 +206,7 @@ def launch_setup(context, *args, **kwargs):
202206
robot_description,
203207
robot_description_semantic,
204208
robot_description_kinematics,
205-
# robot_description_planning,
209+
robot_description_planning,
206210
ompl_planning_pipeline_config,
207211
trajectory_execution,
208212
moveit_controllers,
@@ -228,7 +232,7 @@ def launch_setup(context, *args, **kwargs):
228232
robot_description_semantic,
229233
ompl_planning_pipeline_config,
230234
robot_description_kinematics,
231-
# robot_description_planning,
235+
robot_description_planning,
232236
warehouse_ros_config,
233237
],
234238
)
@@ -323,6 +327,13 @@ def generate_launch_description():
323327
description="MoveIt SRDF/XACRO description file with the robot.",
324328
)
325329
)
330+
declared_arguments.append(
331+
DeclareLaunchArgument(
332+
"moveit_joint_limits_file",
333+
default_value="joint_limits.yaml",
334+
description="MoveIt joint limits that augment or override the values from the URDF robot_description.",
335+
)
336+
)
326337
declared_arguments.append(
327338
DeclareLaunchArgument(
328339
"warehouse_sqlite_path",

0 commit comments

Comments
 (0)