Browse Source

Add moveit simple controller for the base

feature/ros2_diffdrive
JafarAbdi 3 years ago
parent
commit
580eb721e3
2 changed files with 10 additions and 1 deletions
  1. +9
    -1
      stretch_moveit_config/config/moveit_simple_controllers.yaml
  2. +1
    -0
      stretch_moveit_config/config/stretch_description.srdf

+ 9
- 1
stretch_moveit_config/config/moveit_simple_controllers.yaml View File

@ -1,6 +1,7 @@
controller_names:
- stretch_arm_controller
- gripper_controller
- stretch_base_controller
stretch_arm_controller:
action_ns: follow_joint_trajectory
@ -20,4 +21,11 @@ gripper_controller:
type: FollowJointTrajectory
joints:
- joint_gripper_finger_left
- joint_gripper_finger_right
- joint_gripper_finger_right
stretch_base_controller:
action_ns: follow_joint_trajectory
default: True
type: FollowMultiDOFJointTrajectory
joints:
- position

+ 1
- 0
stretch_moveit_config/config/stretch_description.srdf View File

@ -56,6 +56,7 @@
<virtual_joint name="position" type="planar" parent_frame="odom" child_link="base_link" />
<joint_property joint_name="position" property_name="motion_model" value="diff_drive" />
<joint_property joint_name="position" property_name="min_translational_distance" value="0.01" />
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->

Loading…
Cancel
Save