diff --git a/srdf/talos.srdf b/srdf/talos.srdf index 5ec30cbcc5c4e551c2a38458c95a2672d903792a..331da5015bce66ffb15ab962d51bd23c55aadaf9 100644 --- a/srdf/talos.srdf +++ b/srdf/talos.srdf @@ -161,6 +161,41 @@ <joint name="torso_2_joint" value="0.006761" /> </group_state> + + <rotor_params> + <joint name="arm_left_1_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_left_2_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_left_3_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_left_4_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_left_5_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_left_6_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_left_7_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_right_1_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_right_2_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_right_3_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_right_4_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_right_5_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_right_6_joint" mass="1e-5" gear_ratio="100." /> + <joint name="arm_right_7_joint" mass="1e-5" gear_ratio="100." /> + <joint name="head_1_joint" mass="1e-5" gear_ratio="100." /> + <joint name="head_2_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_left_1_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_left_2_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_left_3_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_left_4_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_left_5_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_left_6_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_right_1_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_right_2_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_right_3_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_right_4_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_right_5_joint" mass="1e-5" gear_ratio="100." /> + <joint name="leg_right_6_joint" mass="1e-5" gear_ratio="100." /> + <joint name="torso_1_joint" mass="1e-5" gear_ratio="100." /> + <joint name="torso_2_joint" mass="1e-5" gear_ratio="100." /> + </rotor_params> + + <!-- Talos Specificities. foot height = y axis