Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[NO MERGE] Joints with suffixes #4

Open
wants to merge 5 commits into
base: separate-ros2-control-launch
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
121 changes: 62 additions & 59 deletions motoman_common_moveit/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -1,61 +1,64 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
/**:
ros__parameters:
robot_description_planning:
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed

# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1
# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
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:
group_1/joint_1:
has_velocity_limits: true
max_velocity: 1.832596
has_acceleration_limits: true
max_acceleration: 3.0
has_deceleration_limits: true
max_deceleration: 3.0
group_1/joint_2:
has_velocity_limits: true
max_velocity: 1.640609
has_acceleration_limits: true
max_acceleration: 5.0
has_deceleration_limits: true
max_deceleration: 5.0
group_1/joint_3:
has_velocity_limits: true
max_velocity: 1.745329
has_acceleration_limits: true
max_acceleration: 5.0
has_deceleration_limits: true
max_deceleration: 5.0
group_1/joint_4:
has_position_limits: true
min_position: -0.436332 # -25
max_position: 0.436332 # 25
has_velocity_limits: true
max_velocity: 2.373648
has_acceleration_limits: true
max_acceleration: 3.0
has_deceleration_limits: true
max_deceleration: 3.0
group_1/joint_5:
has_position_limits: true
min_position: -2.18166 # -125
max_position: 0.0
has_velocity_limits: true
max_velocity: 2.251475
has_acceleration_limits: true
max_acceleration: 5.0
has_deceleration_limits: true
max_deceleration: 5.0
group_1/joint_6:
has_position_limits: true
min_position: -3.49066 # -200
max_position: 3.49066 # 200
has_velocity_limits: true
max_velocity: 3.595378
has_acceleration_limits: true
max_acceleration: 7.0
has_deceleration_limits: true
max_deceleration: 7.0
# 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:
group_1/joint_1:
has_velocity_limits: true
max_velocity: 1.832596
has_acceleration_limits: true
max_acceleration: 3.0
has_deceleration_limits: true
max_deceleration: 3.0
group_1/joint_2:
has_velocity_limits: true
max_velocity: 1.640609
has_acceleration_limits: true
max_acceleration: 5.0
has_deceleration_limits: true
max_deceleration: 5.0
group_1/joint_3:
has_velocity_limits: true
max_velocity: 1.745329
has_acceleration_limits: true
max_acceleration: 5.0
has_deceleration_limits: true
max_deceleration: 5.0
group_1/joint_4:
has_position_limits: true
min_position: -0.436332 # -25
max_position: 0.436332 # 25
has_velocity_limits: true
max_velocity: 2.373648
has_acceleration_limits: true
max_acceleration: 3.0
has_deceleration_limits: true
max_deceleration: 3.0
group_1/joint_5:
has_position_limits: true
min_position: -2.18166 # -125
max_position: 0.0
has_velocity_limits: true
max_velocity: 2.251475
has_acceleration_limits: true
max_acceleration: 5.0
has_deceleration_limits: true
max_deceleration: 5.0
group_1/joint_6:
has_position_limits: true
min_position: -3.49066 # -200
max_position: 3.49066 # 200
has_velocity_limits: true
max_velocity: 3.595378
has_acceleration_limits: true
max_acceleration: 7.0
has_deceleration_limits: true
max_deceleration: 7.0
12 changes: 8 additions & 4 deletions motoman_common_moveit/config/kinematics.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,8 @@
manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
/**:
ros__parameters:
robot_description_kinematics:
manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
14 changes: 0 additions & 14 deletions motoman_common_moveit/config/motoman_controllers.yaml

This file was deleted.

22 changes: 22 additions & 0 deletions motoman_common_moveit/config/move_group_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
/**:
ros__parameters:
planning_pipelines: ["ompl", "pilz", "stomp"]

capabilities: >-
move_group/MoveGroupExecuteTrajectoryAction
pilz_industrial_motion_planner/MoveGroupSequenceAction
pilz_industrial_motion_planner/MoveGroupSequenceService

# Trajectory execution manager parameters
allow_trajectory_execution: true
moveit_manage_controllers: false
trajectory_execution:
allowed_execution_duration_scaling: 1.2
allowed_goal_duration_margin: 0.5
allowed_start_tolerance: 0.01

# Planning scene monitor parameters
publish_planning_scene: true
publish_geometry_updates: true
publish_state_updates: true
publish_transforms_updates: true
23 changes: 23 additions & 0 deletions motoman_common_moveit/config/moveit_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/**:
ros__parameters:
moveit_simple_controller_manager:
controller_names:
- follow_joint_trajectory

follow_joint_trajectory:
action_ns: ""
type: FollowJointTrajectory
default: true
joints:
- group_1/joint_1
- group_1/joint_2
- group_1/joint_3
- group_1/joint_4
- group_1/joint_5
- group_1/joint_6

moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager

ompl:
manipulator:
projection_evaluator: joints(group_1/joint_1,group_1/joint_2)
Loading