Additional MoveIt Configuration¶
Change the controller in catkin_ws/src/panda_moveit_config/config/simple_moveit_controllers.yaml file. You can follow the step given here.
1controller_list:
2 - name: position_joint_trajectory_controller
3 action_ns: follow_joint_trajectory
4 type: FollowJointTrajectory
5 default: True
6 joints:
7 - panda_joint1
8 - panda_joint2
9 - panda_joint3
10 - panda_joint4
11 - panda_joint5
12 - panda_joint6
13 - panda_joint7
14 - name: franka_gripper
15 action_ns: gripper_action
16 type: GripperCommand
17 default: True
18 joints:
19 - panda_finger_joint1
The controller name should match the controller spawers when you start your robot (Real or Simulation)
For Real Hardware: https://github.com/frankaemika/franka_ros/blob/a58d3052a241304392847df6464234c83d728a38/franka_control/launch/franka_control.launch#L22
Change from
<node name="state_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="franka_state_controller"/>
to
<node name="state_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="position_joint_trajectory_controller franka_state_controller"/>
For Simulation: https://github.com/frankaemika/franka_ros/blob/a58d3052a241304392847df6464234c83d728a38/franka_gazebo/launch/panda.launch#L14
Change from
<arg name="controller" default=" " doc="Which example controller should be started? (One of {cartesian_impedance,model,force,joint_position,joint_velocity}_example_controller)" />
to
<arg name="controller" default="position_joint_trajectory_controller" doc="Which example controller should be started? (One of {cartesian_impedance,model,force,joint_position,joint_velocity}_example_controller)" />
Add acceleration limits¶
To use pilz_industrial_motion planners we need to modify catkin_ws/src/panda_moveit_config/config/joint_limits.yaml file as shown bellow.
https://github.com/ros-planning/panda_moveit_config/blob/noetic-devel/config/joint_limits.yaml
1joint_limits:
2 panda_finger_joint1:
3 has_velocity_limits: true
4 max_velocity: 0.2
5 has_acceleration_limits: true
6 max_acceleration: 0
7 panda_finger_joint2:
8 has_velocity_limits: true
9 max_velocity: 0.2
10 has_acceleration_limits: true
11 max_acceleration: 0
12 panda_joint1:
13 has_velocity_limits: true
14 max_velocity: 2.175
15 has_acceleration_limits: true
16 max_acceleration: 3.75
17 panda_joint2:
18 has_velocity_limits: true
19 max_velocity: 2.175
20 has_acceleration_limits: true
21 max_acceleration: 1.875
22 panda_joint3:
23 has_velocity_limits: true
24 max_velocity: 2.175
25 has_acceleration_limits: true
26 max_acceleration: 2.5
27 panda_joint4:
28 has_velocity_limits: true
29 max_velocity: 2.175
30 has_acceleration_limits: true
31 max_acceleration: 3.125
32 panda_joint5:
33 has_velocity_limits: true
34 max_velocity: 2.61
35 has_acceleration_limits: true
36 max_acceleration: 3.75
37 panda_joint6:
38 has_velocity_limits: true
39 max_velocity: 2.61
40 has_acceleration_limits: true
41 max_acceleration: 5
42 panda_joint7:
43 has_velocity_limits: true
44 max_velocity: 2.61
45 has_acceleration_limits: true
46 max_acceleration: 5