Skip to content

Commit

Permalink
Define default maximum accelerations for MoveIt (backport of #645) (#981
Browse files Browse the repository at this point in the history
)

(cherry picked from commit 5e3c464)

Co-authored-by: RobertWilbrandt <[email protected]>
  • Loading branch information
mergify[bot] and RobertWilbrandt authored Apr 25, 2024
1 parent 69dbd41 commit c8d961e
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 10 deletions.
25 changes: 25 additions & 0 deletions ur_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# These limits are used by MoveIt and augment/override the definitions in ur_description.
#
# While the robot does not inherently have any limits on joint accelerations (only on torques),
# MoveIt needs them for time parametrization. They were chosen conservatively to work in most use
# cases. For specific applications, higher values might lead to better execution performance.

joint_limits:
shoulder_pan_joint:
has_acceleration_limits: true
max_acceleration: 5.0
shoulder_lift_joint:
has_acceleration_limits: true
max_acceleration: 5.0
elbow_joint:
has_acceleration_limits: true
max_acceleration: 5.0
wrist_1_joint:
has_acceleration_limits: true
max_acceleration: 5.0
wrist_2_joint:
has_acceleration_limits: true
max_acceleration: 5.0
wrist_3_joint:
has_acceleration_limits: true
max_acceleration: 5.0
31 changes: 21 additions & 10 deletions ur_moveit_config/launch/ur_moveit.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,15 @@

import os

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.conditions import IfCondition
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from ur_moveit_config.launch_common import load_yaml

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.conditions import IfCondition
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution


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

Expand All @@ -53,6 +53,7 @@ def launch_setup(context, *args, **kwargs):
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
moveit_config_package = LaunchConfiguration("moveit_config_package")
moveit_joint_limits_file = LaunchConfiguration("moveit_joint_limits_file")
moveit_config_file = LaunchConfiguration("moveit_config_file")
warehouse_sqlite_path = LaunchConfiguration("warehouse_sqlite_path")
prefix = LaunchConfiguration("prefix")
Expand Down Expand Up @@ -146,9 +147,12 @@ def launch_setup(context, *args, **kwargs):
[FindPackageShare(moveit_config_package), "config", "kinematics.yaml"]
)

# robot_description_planning = {
# "robot_description_planning": load_yaml_abs(str(joint_limit_params.perform(context)))
# }
robot_description_planning = {
"robot_description_planning": load_yaml(
str(moveit_config_package.perform(context)),
os.path.join("config", str(moveit_joint_limits_file.perform(context))),
)
}

# Planning Configuration
ompl_planning_pipeline_config = {
Expand Down Expand Up @@ -202,7 +206,7 @@ def launch_setup(context, *args, **kwargs):
robot_description,
robot_description_semantic,
robot_description_kinematics,
# robot_description_planning,
robot_description_planning,
ompl_planning_pipeline_config,
trajectory_execution,
moveit_controllers,
Expand All @@ -228,7 +232,7 @@ def launch_setup(context, *args, **kwargs):
robot_description_semantic,
ompl_planning_pipeline_config,
robot_description_kinematics,
# robot_description_planning,
robot_description_planning,
warehouse_ros_config,
],
)
Expand Down Expand Up @@ -323,6 +327,13 @@ def generate_launch_description():
description="MoveIt SRDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"moveit_joint_limits_file",
default_value="joint_limits.yaml",
description="MoveIt joint limits that augment or override the values from the URDF robot_description.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"warehouse_sqlite_path",
Expand Down

0 comments on commit c8d961e

Please sign in to comment.