Skip to content
Snippets Groups Projects
Commit aed0b464 authored by Rohan Budhiraja's avatar Rohan Budhiraja
Browse files

[srdf] add rotor parameters (only the template) to the srdf

parent 683c1b30
No related branches found
No related tags found
No related merge requests found
......@@ -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
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment