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

PILZ planner integration #4

Merged
merged 3 commits into from
Oct 1, 2024
Merged
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
14 changes: 7 additions & 7 deletions franka_description/robots/panda_arm.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@
<parent link="${arm_id}_link0"/>
<child link="${arm_id}_link1"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-2.7473" upper="2.7473" velocity="2.1750"/>
<limit effort="87" lower="-2.7473" upper="2.7473" velocity="2.1750" acceleration="1.0"/>
</joint>
<link name="${arm_id}_link2">
<visual>
Expand Down Expand Up @@ -99,7 +99,7 @@
<parent link="${arm_id}_link1"/>
<child link="${arm_id}_link2"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-1.6728" upper="1.6728" velocity="2.1750"/>
<limit effort="87" lower="-1.6728" upper="1.6728" velocity="2.1750" acceleration="1.0"/>
</joint>
<link name="${arm_id}_link3">
<visual>
Expand Down Expand Up @@ -132,7 +132,7 @@
<parent link="${arm_id}_link2"/>
<child link="${arm_id}_link3"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-2.7473" upper="2.7473" velocity="2.1750"/>
<limit effort="87" lower="-2.7473" upper="2.7473" velocity="2.1750" acceleration="1.0"/>
</joint>
<link name="${arm_id}_link4">
<visual>
Expand Down Expand Up @@ -165,7 +165,7 @@
<parent link="${arm_id}_link3"/>
<child link="${arm_id}_link4"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-2.9218" upper="-0.2198" velocity="2.1750"/>
<limit effort="87" lower="-2.9218" upper="-0.2198" velocity="2.1750" acceleration="1.0"/>
</joint>
<link name="${arm_id}_link5">
<visual>
Expand Down Expand Up @@ -217,7 +217,7 @@
<parent link="${arm_id}_link4"/>
<child link="${arm_id}_link5"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.7473" upper="2.7473" velocity="2.6100"/>
<limit effort="12" lower="-2.7473" upper="2.7473" velocity="2.6100" acceleration="1.0"/>
</joint>
<link name="${arm_id}_link6">
<visual>
Expand Down Expand Up @@ -250,7 +250,7 @@
<parent link="${arm_id}_link5"/>
<child link="${arm_id}_link6"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-0.0775" upper="3.6025" velocity="2.6100"/>
<limit effort="12" lower="-0.0775" upper="3.6025" velocity="2.6100" acceleration="1.0"/>
</joint>
<link name="${arm_id}_link7">
<visual>
Expand Down Expand Up @@ -283,7 +283,7 @@
<parent link="${arm_id}_link6"/>
<child link="${arm_id}_link7"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.7473" upper="2.7473" velocity="2.6100"/>
<limit effort="12" lower="-2.7473" upper="2.7473" velocity="2.6100" acceleration="1.0"/>
</joint>
<link name="${arm_id}_link8">
<collision>
Expand Down
42 changes: 34 additions & 8 deletions franka_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -132,16 +132,39 @@ planner_configs:
range: 0.0
goal_bias: 0.05
delay_collision_checking: 1
pilz_lin:
PILZ_LIN:
type: pilz_industrial_motion_planner/Linear
planner_id: "LIN"
planning_time: 10.0
max_velocity_scaling_factor: 0.5
max_acceleration_scaling_factor: 0.5
pilz_circ:
PILZ_CIRC:
type: pilz_industrial_motion_planner/Circular
planner_id: "CIRC"
planning_time: 10.0
max_velocity_scaling_factor: 0.5
max_acceleration_scaling_factor: 0.5
PILZ_PTP:
type: pilz_industrial_motion_planner/Circular
planner_id: "PTP"
planning_time: 10.0
max_velocity_scaling_factor: 0.5
max_acceleration_scaling_factor: 0.5

robot_description_planning:
cartesian_limits:
max_trans_vel: 0.2 # Maximum translational velocity (m/s)
max_trans_acc: 0.5 # Maximum translational acceleration (m/s^2)
max_trans_dec: 0.5 # Maximum translational deceleration (m/s^2)
max_rot_vel: 1.0 # Maximum rotational velocity (rad/s)

planning_pipelines:
default:
planner_configs: OMPL
ompl:
planner_configs: OMPL
pilz:
planner_configs: [PILZ_LIN, PILZ_CIRC, PILZ_PTP]

panda_arm:
enforce_constrained_state_space: true
Expand Down Expand Up @@ -171,8 +194,9 @@ panda_arm:
- SPARSkConfigDefault
- SPARStwokConfigDefault
- TrajOptDefault
- pilz_lin
- pilz_circ
- PILZ_LIN
- PILZ_CIRC
- OMPL
panda_arm_hand:
enforce_constrained_state_space: true
projection_evaluator: joints(panda_joint1, panda_joint2)
Expand Down Expand Up @@ -201,8 +225,9 @@ panda_arm_hand:
- SPARSkConfigDefault
- SPARStwokConfigDefault
- TrajOptDefault
- pilz_lin
- pilz_circ
- PILZ_LIN
- PILZ_CIRC
- OMPL
panda_vision:
enforce_constrained_state_space: true
projection_evaluator: joints(panda_joint1, panda_joint2)
Expand Down Expand Up @@ -231,6 +256,7 @@ panda_vision:
- SPARSkConfigDefault
- SPARStwokConfigDefault
- TrajOptDefault
- pilz_lin
- pilz_circ
- PILZ_LIN
- PILZ_CIRC
- OMPL

36 changes: 33 additions & 3 deletions franka_moveit_config/launch/moveit_real_arm_platform.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ def generate_launch_description():
load_gripper_parameter_name = 'load_gripper'
fake_sensor_commands_parameter_name = 'fake_sensor_commands'
load_camera_parameter_name = 'load_camera'
planner_parameter_name = 'planner'

camera_id_parameter_name = 'serial'
camera_model_parameter_name = 'camera_type'
Expand All @@ -59,6 +60,8 @@ def generate_launch_description():
camera_id = LaunchConfiguration(camera_id_parameter_name)
camera_model = LaunchConfiguration(camera_model_parameter_name)

planner_ = LaunchConfiguration(planner_parameter_name)

# Command-line arguments
db_arg = DeclareLaunchArgument(
'db', default_value='False', description='Database flag'
Expand Down Expand Up @@ -149,9 +152,32 @@ def generate_launch_description():

combined_planning_pipelines_config = {
'move_group': {
'planning_pipelines': 'ompl, pilz',
'planning_plugin': planner_,
'request_adapters': 'default_planner_request_adapters/AddTimeOptimalParameterization '
'default_planner_request_adapters/ResolveConstraintFrames '
'default_planner_request_adapters/FixWorkspaceBounds '
'default_planner_request_adapters/FixStartStateBounds '
'default_planner_request_adapters/FixStartStateCollision '
'default_planner_request_adapters/FixStartStatePathConstraints'
'default_planning_request_adapters/CheckStartStateBounds'
'default_planning_request_adapters/CheckStartStateCollision'
'default_planning_request_adapters/ValidateWorkspaceBounds',
'start_state_max_bounds_error': 0.1,
'default_planner_config': 'PTP',
},
'robot_description_planning':{
'cartesian_limits': {
'max_trans_vel': 0.2,
'max_trans_acc': 1.0,
'max_trans_dec': -1.0,
'max_rot_vel': 0.5
}
}
}
combined_planning_yaml = load_yaml(
'franka_moveit_config', 'config/ompl_planning.yaml'
)
combined_planning_pipelines_config['move_group'].update(combined_planning_yaml)

# Start the actual move_group node/action server
run_move_group_node = Node(
Expand All @@ -163,8 +189,6 @@ def generate_launch_description():
robot_description_semantic,
kinematics_yaml,
combined_planning_pipelines_config,
ompl_planning_pipeline_config,
pilz_planning_pipeline_config,
trajectory_execution,
moveit_controllers,
planning_scene_monitor_parameters,
Expand Down Expand Up @@ -262,6 +286,11 @@ def generate_launch_description():
default_value='true',
description='Use Flir camera as an end-effector, otherwise, the robot is loaded '
'without an end-effector.')

planner_arg = DeclareLaunchArgument(
planner_parameter_name,
default_value='ompl_interface/OMPLPlanner',
description='Choose planner to be used for arm control ')

load_gripper_arg = DeclareLaunchArgument(
load_gripper_parameter_name,
Expand Down Expand Up @@ -307,6 +336,7 @@ def generate_launch_description():
fake_sensor_commands_arg,
load_gripper_arg,
load_camera_arg,
planner_arg,
camera_id_arg,
camera_model_arg,
db_arg,
Expand Down
Loading