Browse Source

Add IK solver for mobile_base + arm

feature/ros2_diffdrive
JafarAbdi 3 years ago
committed by Jafar Abdi
parent
commit
495456daa4
2 changed files with 13 additions and 2 deletions
  1. +5
    -1
      stretch_moveit_config/config/kinematics.yaml
  2. +8
    -1
      stretch_moveit_config/config/stretch_description.srdf

+ 5
- 1
stretch_moveit_config/config/kinematics.yaml View File

@ -1,4 +1,8 @@
stretch_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_timeout: 0.005
mobile_base_arm:
kinematics_solver: stretch_kinematics_plugin/StretchKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.1

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

@ -43,10 +43,17 @@
<joint name="joint_lift" value="1.1"/>
<joint name="joint_wrist_yaw" value="4"/>
</group_state>
<group name="position">
<joint name="position" />
</group>
<group name="mobile_base_arm">
<group name="stretch_arm" />
<group name="position" />
</group>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="gripper" parent_link="link_grasp_center" group="stretch_arm"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="position" type="floating" parent_frame="map" child_link="base_link"/>
<virtual_joint name="position" type="planar" parent_frame="map" child_link="base_link"/>
<!--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. -->
<disable_collisions link1="base_link" link2="camera_link" reason="Never"/>
<disable_collisions link1="base_link" link2="laser" reason="Adjacent"/>

Loading…
Cancel
Save