Skip to content

Commit

Permalink
separate ompl_planning.yaml config, refactor config
Browse files Browse the repository at this point in the history
  • Loading branch information
Nibanovic committed Apr 5, 2024
1 parent 933b2de commit a2ce5df
Show file tree
Hide file tree
Showing 7 changed files with 88 additions and 229 deletions.
79 changes: 79 additions & 0 deletions myrobot_ws/src/myrobot_moveit/config/move_group.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
/**:
ros__parameters:
#-------- Moveit controllers
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
moveit_simple_controller_manager:
controller_names:
- joint_trajectory_controller # add or remove controllers as necessary

joint_trajectory_controller:
type: FollowJointTrajectory
action_ns: follow_joint_trajectory
default: true
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6

#-------- kinematics
robot_description_kinematics:
myrobot_manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3

#-------- joint limits
robot_description_planning:
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
joint1:
has_velocity_limits: true
max_velocity: 1.7453292519943295
has_acceleration_limits: true
max_acceleration: 5.0
joint2:
has_velocity_limits: true
max_velocity: 1.5707963267948966
has_acceleration_limits: true
max_acceleration: 5.0
joint3:
has_velocity_limits: true
max_velocity: 1.5707963267948966
has_acceleration_limits: true
max_acceleration: 5.0
joint4:
has_velocity_limits: true
max_velocity: 2.9670597283903604
has_acceleration_limits: true
max_acceleration: 5.0
joint5:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: true
max_acceleration: 5.0
joint6:
has_velocity_limits: true
max_velocity: 3.3161255787892263
has_acceleration_limits: true
max_acceleration: 5.0

#-------- other
moveit_manage_controllers: false
trajectory_execution:
allowed_execution_duration_scaling: 1.2
allowed_goal_duration_margin: 0.5
allowed_start_tolerance: 0.01
capabilities: move_group/MoveGroupExecuteTrajectoryAction
publish_planning_scene: True
publish_geometry_updates: True
publish_state_updates: True
publish_transforms_updates: True


Original file line number Diff line number Diff line change
@@ -1,84 +1,5 @@
/**:
ros__parameters:
# from launch file
capabilities: move_group/MoveGroupExecuteTrajectoryAction
publish_planning_scene: True
publish_geometry_updates: True
publish_state_updates: True
publish_transforms_updates: True

# kinematics
robot_description_kinematics:
myrobot_manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3

# joint limits
robot_description_planning:
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1

# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
joint1:
has_velocity_limits: true
max_velocity: 1.7453292519943295
has_acceleration_limits: true
max_acceleration: 5.0
joint2:
has_velocity_limits: true
max_velocity: 1.5707963267948966
has_acceleration_limits: true
max_acceleration: 5.0
joint3:
has_velocity_limits: true
max_velocity: 1.5707963267948966
has_acceleration_limits: true
max_acceleration: 5.0
joint4:
has_velocity_limits: true
max_velocity: 2.9670597283903604
has_acceleration_limits: true
max_acceleration: 5.0
joint5:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: true
max_acceleration: 5.0
joint6:
has_velocity_limits: true
max_velocity: 3.3161255787892263
has_acceleration_limits: true
max_acceleration: 5.0

# Moveit Controllers
moveit_manage_controllers: false
trajectory_execution:
allowed_execution_duration_scaling: 1.2
allowed_goal_duration_margin: 0.5
allowed_start_tolerance: 0.01

moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
moveit_simple_controller_manager:
controller_names:
- joint_trajectory_controller

joint_trajectory_controller:
type: FollowJointTrajectory
action_ns: follow_joint_trajectory
default: true
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6

# OMPL planning
move_group:
planning_plugins:
- ompl_interface/OMPLPlanner
Expand Down
40 changes: 0 additions & 40 deletions myrobot_ws/src/myrobot_moveit/config_old/joint_limits.yaml

This file was deleted.

5 changes: 0 additions & 5 deletions myrobot_ws/src/myrobot_moveit/config_old/kinematics.yaml

This file was deleted.

24 changes: 0 additions & 24 deletions myrobot_ws/src/myrobot_moveit/config_old/moveit_controllers.yaml

This file was deleted.

69 changes: 0 additions & 69 deletions myrobot_ws/src/myrobot_moveit/config_old/ompl_planning.yaml

This file was deleted.

21 changes: 9 additions & 12 deletions myrobot_ws/src/myrobot_moveit/launch/moveit.launch.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,3 @@
import os
import yaml

from launch.actions import DeclareLaunchArgument

Check failure on line 1 in myrobot_ws/src/myrobot_moveit/launch/moveit.launch.py

View workflow job for this annotation

GitHub Actions / ament_copyright

could not find copyright notice

Check failure on line 1 in myrobot_ws/src/myrobot_moveit/launch/moveit.launch.py

View workflow job for this annotation

GitHub Actions / ament_copyright

could not find copyright notice
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
Expand Down Expand Up @@ -43,8 +40,6 @@ def launch_setup(context, *args, **kwargs):
" ",
]
)
robot_description = {"robot_description": robot_description_content.perform(context)}

# SRDF
robot_description_semantic_content = Command(
[
Expand All @@ -53,14 +48,13 @@ def launch_setup(context, *args, **kwargs):
PathJoinSubstitution(
[FindPackageShare(moveit_package), "srdf", semantic_description_file]
),

]
)
robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content.perform(context)}

other_configs = PathJoinSubstitution(
[FindPackageShare(moveit_package), "config", "all.yaml"]
)
robot_description = {"robot_description": robot_description_content.perform(context)}
robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content.perform(context)}
planning_config = PathJoinSubstitution([FindPackageShare(moveit_package), "config", "ompl_planning.yaml"])
move_group_config = PathJoinSubstitution([FindPackageShare(moveit_package), "config", "move_group.yaml"])

# -------------------------------------------------------#
# Move Group Node #
Expand All @@ -73,7 +67,8 @@ def launch_setup(context, *args, **kwargs):
parameters=[
robot_description,
robot_description_semantic,
other_configs,
planning_config,
move_group_config,
{"use_sim_time": use_sim_time},
],
)
Expand All @@ -90,7 +85,9 @@ def launch_setup(context, *args, **kwargs):
parameters=[
robot_description,
robot_description_semantic,
other_configs
planning_config,
move_group_config,
{"use_sim_time": use_sim_time},
],
)

Expand Down

0 comments on commit a2ce5df

Please sign in to comment.