From b8a1741e713edc5dcfbff559b57c8fd5acc3fe02 Mon Sep 17 00:00:00 2001 From: Rohan Budhiraja <budhiraja@laas.fr> Date: Sat, 17 Dec 2016 13:27:41 +0100 Subject: [PATCH] [talos_description/srdf] Update half-sitting, remove disabled joints *update half-sitting pose to a more dynamically stable one *remove "Default" disabled collisions with leg_3_link and other common one *remove other disabled collisions based on a more thorough Moveit sampling --- talos_description/srdf/talos.srdf | 140 +++++++++++++++++++----------- 1 file changed, 87 insertions(+), 53 deletions(-) diff --git a/talos_description/srdf/talos.srdf b/talos_description/srdf/talos.srdf index eb9d325..743357f 100644 --- a/talos_description/srdf/talos.srdf +++ b/talos_description/srdf/talos.srdf @@ -9,6 +9,30 @@ <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included--> <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> + <group name="r_arm"> + <joint name="arm_right_1_joint" /> + <joint name="arm_right_2_joint" /> + <joint name="arm_right_3_joint" /> + <joint name="arm_right_4_joint" /> + <joint name="arm_right_5_joint" /> + <joint name="arm_right_6_joint" /> + <joint name="arm_right_7_joint" /> + <joint name="wrist_right_ft_joint" /> + <joint name="wrist_right_tool_joint" /> + <chain base_link="torso_2_link" tip_link="wrist_right_ft_tool_link" /> + </group> + <group name="gripper_right"> + <link name="gripper_right_base_link" /> + <link name="gripper_right_inner_double_link" /> + <link name="gripper_right_fingertip_1_link" /> + <link name="gripper_right_fingertip_2_link" /> + <link name="gripper_right_inner_single_link" /> + <link name="gripper_right_fingertip_3_link" /> + <link name="gripper_right_motor_double_link" /> + <link name="gripper_right_motor_single_link" /> + <joint name="gripper_right_joint" /> + <chain base_link="wrist_right_ft_tool_link" tip_link="gripper_right_base_link" /> + </group> <group name="l_arm"> <joint name="arm_left_1_joint" /> <joint name="arm_left_2_joint" /> @@ -17,23 +41,39 @@ <joint name="arm_left_5_joint" /> <joint name="arm_left_6_joint" /> <joint name="arm_left_7_joint" /> + <joint name="wrist_left_ft_joint" /> + <joint name="wrist_left_tool_joint" /> + <chain base_link="torso_2_link" tip_link="wrist_left_ft_tool_link" /> </group> - <group name="r_arm"> - <joint name="arm_right_1_joint" /> - <joint name="arm_right_2_joint" /> - <joint name="arm_right_3_joint" /> - <joint name="arm_right_4_joint" /> - <joint name="arm_right_5_joint" /> - <joint name="arm_right_6_joint" /> - <joint name="arm_right_7_joint" /> + <group name="gripper_left"> + <link name="gripper_left_base_link" /> + <link name="gripper_left_inner_double_link" /> + <link name="gripper_left_fingertip_1_link" /> + <link name="gripper_left_fingertip_2_link" /> + <link name="gripper_left_inner_single_link" /> + <link name="gripper_left_fingertip_3_link" /> + <link name="gripper_left_motor_double_link" /> + <link name="gripper_left_motor_single_link" /> + <joint name="gripper_left_joint" /> + <chain base_link="wrist_left_ft_tool_link" tip_link="gripper_left_base_link" /> </group> - <group name="l_leg"> - <joint name="leg_left_1_joint" /> - <joint name="leg_left_2_joint" /> - <joint name="leg_left_3_joint" /> - <joint name="leg_left_4_joint" /> - <joint name="leg_left_5_joint" /> - <joint name="leg_left_6_joint" /> + <group name="torso"> + <joint name="torso_1_joint" /> + <joint name="torso_2_joint" /> + <chain base_link="base_link" tip_link="torso_2_link" /> + </group> + <group name="both_arms_torso"> + <group name="left_arm" /> + <group name="right_arm" /> + <group name="torso" /> + </group> + <group name="right_arm_torso"> + <group name="right_arm" /> + <group name="torso" /> + </group> + <group name="left_arm_torso"> + <group name="left_arm" /> + <group name="torso" /> </group> <group name="r_leg"> <joint name="leg_right_1_joint" /> @@ -42,16 +82,23 @@ <joint name="leg_right_4_joint" /> <joint name="leg_right_5_joint" /> <joint name="leg_right_6_joint" /> + <joint name="leg_right_sole_fix_joint" /> + <chain base_link="base_link" tip_link="right_sole_link" /> + </group> + <group name="l_leg"> + <joint name="leg_left_1_joint" /> + <joint name="leg_left_2_joint" /> + <joint name="leg_left_3_joint" /> + <joint name="leg_left_4_joint" /> + <joint name="leg_left_5_joint" /> + <joint name="leg_left_6_joint" /> + <joint name="leg_left_sole_fix_joint" /> + <chain base_link="base_link" tip_link="left_sole_link" /> </group> <group name="head"> <joint name="head_1_joint" /> <joint name="head_2_joint" /> </group> - <group name="torso"> - <link name="base_link" /> - <joint name="torso_1_joint" /> - <joint name="torso_2_joint" /> - </group> <group name="all"> <group name="l_arm" /> <group name="r_arm" /> @@ -60,6 +107,25 @@ <group name="head" /> <group name="torso" /> </group> + + <!--END EFFECTOR: Purpose: Represent information about an end effector.--> + <end_effector name="right_eef" parent_link="wrist_right_ft_tool_link" group="gripper_right" parent_group="right_arm" /> + <end_effector name="left_eef" parent_link="wrist_left_ft_tool_link" group="gripper_left" parent_group="left_arm" /> + <!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated--> + <passive_joint name="gripper_left_motor_single_joint" /> + <passive_joint name="gripper_left_inner_double_joint" /> + <passive_joint name="gripper_left_fingertip_1_joint" /> + <passive_joint name="gripper_left_fingertip_2_joint" /> + <passive_joint name="gripper_left_inner_single_joint" /> + <passive_joint name="gripper_left_fingertip_3_joint" /> + <passive_joint name="gripper_right_inner_double_joint" /> + <passive_joint name="gripper_right_fingertip_1_joint" /> + <passive_joint name="gripper_right_fingertip_2_joint" /> + <passive_joint name="gripper_right_inner_single_joint" /> + <passive_joint name="gripper_right_fingertip_3_joint" /> + <passive_joint name="gripper_right_motor_single_joint" /> + <!--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. --> + <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> <group_state name="half_sitting" group="all"> <joint name="arm_left_1_joint" value="0.25847" /> @@ -123,14 +189,12 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_left_1_link" link2="arm_left_4_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="arm_left_5_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="arm_left_6_link" reason="Never" /> - <disable_collisions link1="arm_left_1_link" link2="arm_left_7_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="arm_right_1_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="arm_right_2_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="arm_right_3_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="arm_right_4_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="arm_right_5_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="arm_right_6_link" reason="Never" /> - <disable_collisions link1="arm_left_1_link" link2="arm_right_7_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="base_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="head_1_link" reason="Never" /> <disable_collisions link1="arm_left_1_link" link2="head_2_link" reason="Never" /> @@ -169,15 +233,12 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_left_2_link" link2="leg_left_1_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="leg_left_2_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="leg_left_3_link" reason="Never" /> - <disable_collisions link1="arm_left_2_link" link2="leg_left_4_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="leg_left_5_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="leg_left_6_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="leg_right_1_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="leg_right_2_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="leg_right_3_link" reason="Never" /> - <disable_collisions link1="arm_left_2_link" link2="leg_right_4_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="leg_right_5_link" reason="Never" /> - <disable_collisions link1="arm_left_2_link" link2="leg_right_6_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="torso_1_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="arm_left_2_link" link2="wrist_left_ft_tool_link" reason="Never" /> @@ -200,11 +261,8 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_left_3_link" link2="imu_link" reason="Never" /> <disable_collisions link1="arm_left_3_link" link2="leg_left_1_link" reason="Never" /> <disable_collisions link1="arm_left_3_link" link2="leg_left_2_link" reason="Never" /> - <disable_collisions link1="arm_left_3_link" link2="leg_left_5_link" reason="Never" /> - <disable_collisions link1="arm_left_3_link" link2="leg_left_6_link" reason="Never" /> <disable_collisions link1="arm_left_3_link" link2="leg_right_1_link" reason="Never" /> <disable_collisions link1="arm_left_3_link" link2="leg_right_2_link" reason="Never" /> - <disable_collisions link1="arm_left_3_link" link2="leg_right_5_link" reason="Never" /> <disable_collisions link1="arm_left_3_link" link2="torso_1_link" reason="Never" /> <disable_collisions link1="arm_left_3_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="arm_left_3_link" link2="wrist_left_ft_tool_link" reason="Never" /> @@ -228,7 +286,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_left_4_link" link2="leg_left_2_link" reason="Never" /> <disable_collisions link1="arm_left_4_link" link2="leg_right_1_link" reason="Never" /> <disable_collisions link1="arm_left_4_link" link2="leg_right_2_link" reason="Never" /> - <disable_collisions link1="arm_left_4_link" link2="rgbd_link" reason="Never" /> <disable_collisions link1="arm_left_4_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="arm_left_4_link" link2="wrist_left_ft_tool_link" reason="Never" /> <disable_collisions link1="arm_left_5_link" link2="arm_left_6_link" reason="Adjacent" /> @@ -255,7 +312,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_left_6_link" link2="gripper_left_motor_single_link" reason="Never" /> <disable_collisions link1="arm_left_6_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="arm_left_6_link" link2="wrist_left_ft_tool_link" reason="Never" /> - <disable_collisions link1="arm_left_7_link" link2="arm_right_1_link" reason="Never" /> <disable_collisions link1="arm_left_7_link" link2="gripper_left_base_link" reason="Default" /> <disable_collisions link1="arm_left_7_link" link2="gripper_left_fingertip_1_link" reason="Never" /> <disable_collisions link1="arm_left_7_link" link2="gripper_left_fingertip_2_link" reason="Never" /> @@ -264,7 +320,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_left_7_link" link2="gripper_left_inner_single_link" reason="Never" /> <disable_collisions link1="arm_left_7_link" link2="gripper_left_motor_double_link" reason="Never" /> <disable_collisions link1="arm_left_7_link" link2="gripper_left_motor_single_link" reason="Never" /> - <disable_collisions link1="arm_left_7_link" link2="leg_left_3_link" reason="Default" /> <disable_collisions link1="arm_left_7_link" link2="wrist_left_ft_link" reason="Adjacent" /> <disable_collisions link1="arm_left_7_link" link2="wrist_left_ft_tool_link" reason="Never" /> <disable_collisions link1="arm_right_1_link" link2="arm_right_2_link" reason="Adjacent" /> @@ -272,7 +327,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_right_1_link" link2="arm_right_4_link" reason="Never" /> <disable_collisions link1="arm_right_1_link" link2="arm_right_5_link" reason="Never" /> <disable_collisions link1="arm_right_1_link" link2="arm_right_6_link" reason="Never" /> - <disable_collisions link1="arm_right_1_link" link2="arm_right_7_link" reason="Never" /> <disable_collisions link1="arm_right_1_link" link2="base_link" reason="Never" /> <disable_collisions link1="arm_right_1_link" link2="head_1_link" reason="Never" /> <disable_collisions link1="arm_right_1_link" link2="head_2_link" reason="Never" /> @@ -307,13 +361,10 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_right_2_link" link2="leg_left_1_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="leg_left_2_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="leg_left_3_link" reason="Never" /> - <disable_collisions link1="arm_right_2_link" link2="leg_left_4_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="leg_left_5_link" reason="Never" /> - <disable_collisions link1="arm_right_2_link" link2="leg_left_6_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="leg_right_1_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="leg_right_2_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="leg_right_3_link" reason="Never" /> - <disable_collisions link1="arm_right_2_link" link2="leg_right_4_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="leg_right_5_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="leg_right_6_link" reason="Never" /> <disable_collisions link1="arm_right_2_link" link2="torso_1_link" reason="Never" /> @@ -336,7 +387,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_right_3_link" link2="leg_left_2_link" reason="Never" /> <disable_collisions link1="arm_right_3_link" link2="leg_right_1_link" reason="Never" /> <disable_collisions link1="arm_right_3_link" link2="leg_right_2_link" reason="Never" /> - <disable_collisions link1="arm_right_3_link" link2="leg_right_5_link" reason="Never" /> <disable_collisions link1="arm_right_3_link" link2="torso_1_link" reason="Never" /> <disable_collisions link1="arm_right_3_link" link2="wrist_right_ft_link" reason="Never" /> <disable_collisions link1="arm_right_3_link" link2="wrist_right_ft_tool_link" reason="Never" /> @@ -355,7 +405,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_right_4_link" link2="imu_link" reason="Never" /> <disable_collisions link1="arm_right_4_link" link2="leg_left_1_link" reason="Never" /> <disable_collisions link1="arm_right_4_link" link2="leg_left_2_link" reason="Never" /> - <disable_collisions link1="arm_right_4_link" link2="leg_left_5_link" reason="Never" /> <disable_collisions link1="arm_right_4_link" link2="leg_right_2_link" reason="Never" /> <disable_collisions link1="arm_right_4_link" link2="wrist_right_ft_link" reason="Never" /> <disable_collisions link1="arm_right_4_link" link2="wrist_right_ft_tool_link" reason="Never" /> @@ -389,7 +438,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="arm_right_7_link" link2="gripper_right_inner_single_link" reason="Never" /> <disable_collisions link1="arm_right_7_link" link2="gripper_right_motor_double_link" reason="Never" /> <disable_collisions link1="arm_right_7_link" link2="gripper_right_motor_single_link" reason="Never" /> - <disable_collisions link1="arm_right_7_link" link2="leg_right_3_link" reason="Default" /> <disable_collisions link1="arm_right_7_link" link2="wrist_right_ft_link" reason="Adjacent" /> <disable_collisions link1="arm_right_7_link" link2="wrist_right_ft_tool_link" reason="Never" /> <disable_collisions link1="base_link" link2="head_1_link" reason="Never" /> @@ -409,7 +457,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="gripper_left_base_link" link2="gripper_left_inner_single_link" reason="Adjacent" /> <disable_collisions link1="gripper_left_base_link" link2="gripper_left_motor_double_link" reason="Adjacent" /> <disable_collisions link1="gripper_left_base_link" link2="gripper_left_motor_single_link" reason="Adjacent" /> - <disable_collisions link1="gripper_left_base_link" link2="leg_left_3_link" reason="Default" /> <disable_collisions link1="gripper_left_base_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="gripper_left_base_link" link2="wrist_left_ft_tool_link" reason="Adjacent" /> <disable_collisions link1="gripper_left_fingertip_1_link" link2="gripper_left_fingertip_2_link" reason="Never" /> @@ -435,13 +482,11 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="gripper_left_inner_double_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="gripper_left_inner_double_link" link2="wrist_left_ft_tool_link" reason="Never" /> <disable_collisions link1="gripper_left_inner_single_link" link2="gripper_left_motor_single_link" reason="Default" /> - <disable_collisions link1="gripper_left_inner_single_link" link2="leg_left_3_link" reason="Default" /> <disable_collisions link1="gripper_left_inner_single_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="gripper_left_inner_single_link" link2="wrist_left_ft_tool_link" reason="Never" /> <disable_collisions link1="gripper_left_motor_double_link" link2="gripper_left_motor_single_link" reason="Default" /> <disable_collisions link1="gripper_left_motor_double_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="gripper_left_motor_double_link" link2="wrist_left_ft_tool_link" reason="Never" /> - <disable_collisions link1="gripper_left_motor_single_link" link2="leg_left_3_link" reason="Default" /> <disable_collisions link1="gripper_left_motor_single_link" link2="wrist_left_ft_link" reason="Never" /> <disable_collisions link1="gripper_left_motor_single_link" link2="wrist_left_ft_tool_link" reason="Never" /> <disable_collisions link1="gripper_right_base_link" link2="gripper_right_fingertip_1_link" reason="Never" /> @@ -451,7 +496,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="gripper_right_base_link" link2="gripper_right_inner_single_link" reason="Adjacent" /> <disable_collisions link1="gripper_right_base_link" link2="gripper_right_motor_double_link" reason="Adjacent" /> <disable_collisions link1="gripper_right_base_link" link2="gripper_right_motor_single_link" reason="Adjacent" /> - <disable_collisions link1="gripper_right_base_link" link2="leg_right_3_link" reason="Default" /> <disable_collisions link1="gripper_right_base_link" link2="wrist_right_ft_link" reason="Never" /> <disable_collisions link1="gripper_right_base_link" link2="wrist_right_ft_tool_link" reason="Adjacent" /> <disable_collisions link1="gripper_right_fingertip_1_link" link2="gripper_right_fingertip_2_link" reason="Never" /> @@ -477,13 +521,11 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="gripper_right_inner_double_link" link2="wrist_right_ft_link" reason="Never" /> <disable_collisions link1="gripper_right_inner_double_link" link2="wrist_right_ft_tool_link" reason="Never" /> <disable_collisions link1="gripper_right_inner_single_link" link2="gripper_right_motor_single_link" reason="Default" /> - <disable_collisions link1="gripper_right_inner_single_link" link2="leg_right_3_link" reason="Default" /> <disable_collisions link1="gripper_right_inner_single_link" link2="wrist_right_ft_link" reason="Never" /> <disable_collisions link1="gripper_right_inner_single_link" link2="wrist_right_ft_tool_link" reason="Never" /> <disable_collisions link1="gripper_right_motor_double_link" link2="gripper_right_motor_single_link" reason="Default" /> <disable_collisions link1="gripper_right_motor_double_link" link2="wrist_right_ft_link" reason="Never" /> <disable_collisions link1="gripper_right_motor_double_link" link2="wrist_right_ft_tool_link" reason="Never" /> - <disable_collisions link1="gripper_right_motor_single_link" link2="leg_right_3_link" reason="Default" /> <disable_collisions link1="gripper_right_motor_single_link" link2="wrist_right_ft_link" reason="Never" /> <disable_collisions link1="gripper_right_motor_single_link" link2="wrist_right_ft_tool_link" reason="Never" /> <disable_collisions link1="head_1_link" link2="head_2_link" reason="Adjacent" /> @@ -538,16 +580,12 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="leg_left_1_link" link2="leg_left_3_link" reason="Default" /> <disable_collisions link1="leg_left_1_link" link2="leg_left_4_link" reason="Never" /> <disable_collisions link1="leg_left_1_link" link2="leg_left_5_link" reason="Never" /> - <disable_collisions link1="leg_left_1_link" link2="leg_right_1_link" reason="Never" /> - <disable_collisions link1="leg_left_1_link" link2="leg_right_2_link" reason="Never" /> <disable_collisions link1="leg_left_1_link" link2="rgbd_link" reason="Never" /> <disable_collisions link1="leg_left_1_link" link2="torso_1_link" reason="Never" /> <disable_collisions link1="leg_left_1_link" link2="torso_2_link" reason="Never" /> <disable_collisions link1="leg_left_2_link" link2="leg_left_3_link" reason="Adjacent" /> <disable_collisions link1="leg_left_2_link" link2="leg_left_4_link" reason="Never" /> <disable_collisions link1="leg_left_2_link" link2="leg_left_5_link" reason="Never" /> - <disable_collisions link1="leg_left_2_link" link2="leg_right_1_link" reason="Never" /> - <disable_collisions link1="leg_left_2_link" link2="leg_right_2_link" reason="Never" /> <disable_collisions link1="leg_left_2_link" link2="rgbd_link" reason="Never" /> <disable_collisions link1="leg_left_2_link" link2="torso_1_link" reason="Never" /> <disable_collisions link1="leg_left_2_link" link2="torso_2_link" reason="Never" /> @@ -556,8 +594,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="leg_left_3_link" link2="rgbd_link" reason="Never" /> <disable_collisions link1="leg_left_3_link" link2="torso_1_link" reason="Never" /> <disable_collisions link1="leg_left_3_link" link2="torso_2_link" reason="Never" /> - <disable_collisions link1="leg_left_3_link" link2="wrist_left_ft_link" reason="Default" /> - <disable_collisions link1="leg_left_3_link" link2="wrist_left_ft_tool_link" reason="Default" /> <disable_collisions link1="leg_left_4_link" link2="leg_left_5_link" reason="Adjacent" /> <disable_collisions link1="leg_left_4_link" link2="leg_left_6_link" reason="Never" /> <disable_collisions link1="leg_left_4_link" link2="rgbd_link" reason="Never" /> @@ -588,8 +624,6 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="leg_right_3_link" link2="rgbd_link" reason="Never" /> <disable_collisions link1="leg_right_3_link" link2="torso_1_link" reason="Never" /> <disable_collisions link1="leg_right_3_link" link2="torso_2_link" reason="Never" /> - <disable_collisions link1="leg_right_3_link" link2="wrist_right_ft_link" reason="Default" /> - <disable_collisions link1="leg_right_3_link" link2="wrist_right_ft_tool_link" reason="Default" /> <disable_collisions link1="leg_right_4_link" link2="leg_right_5_link" reason="Adjacent" /> <disable_collisions link1="leg_right_4_link" link2="leg_right_6_link" reason="Never" /> <disable_collisions link1="leg_right_4_link" link2="rgbd_link" reason="Never" /> @@ -607,4 +641,4 @@ TALOS disabled collisions generated by Moveit! using the moveit_setup_assistant. <disable_collisions link1="torso_1_link" link2="torso_2_link" reason="Adjacent" /> <disable_collisions link1="wrist_left_ft_link" link2="wrist_left_ft_tool_link" reason="Adjacent" /> <disable_collisions link1="wrist_right_ft_link" link2="wrist_right_ft_tool_link" reason="Adjacent" /> -</robot> +</robot> \ No newline at end of file -- GitLab