Skip to content

Commit

Permalink
Remove contype/conaffinity from plane since they are already set to d…
Browse files Browse the repository at this point in the history
…efaults.
  • Loading branch information
kevinzakka committed Sep 5, 2024
1 parent 7767d16 commit b9336e2
Show file tree
Hide file tree
Showing 4 changed files with 67 additions and 35 deletions.
2 changes: 1 addition & 1 deletion pal_talos/scene_motor.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
</asset>

<worldbody>
<geom name="floor" contype="1" conaffinity="1" pos="0 0 -1.01" size="0 0 1" type="plane" material="MatPlane"/>
<geom name="floor" pos="0 0 -1.01" size="0 0 1" type="plane" material="MatPlane"/>
<light name="spotlight" mode="targetbody" target="base_link" pos="1 0 20"/>
</worldbody>
</mujoco>
2 changes: 1 addition & 1 deletion pal_talos/scene_position.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
</asset>

<worldbody>
<geom name="floor" contype="1" conaffinity="1" pos="0 0 -1.01" size="0 0 1" type="plane" material="MatPlane"/>
<geom name="floor" pos="0 0 -1.01" size="0 0 1" type="plane" material="MatPlane"/>
<light name="spotlight" mode="targetbody" target="base_link" pos="1 0 20"/>
</worldbody>
</mujoco>
2 changes: 1 addition & 1 deletion pal_talos/scene_velocity.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
</asset>

<worldbody>
<geom name="floor" contype="1" conaffinity="1" pos="0 0 -1.01" size="0 0 1" type="plane" material="MatPlane"/>
<geom name="floor" pos="0 0 -1.01" size="0 0 1" type="plane" material="MatPlane"/>
<light name="spotlight" mode="targetbody" target="base_link" pos="1 0 20"/>
</worldbody>
</mujoco>
96 changes: 64 additions & 32 deletions pal_talos/talos_position.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,38 +8,70 @@
</default>

<actuator>
<position class="position" name="torso_1_joint_position" joint="torso_1_joint" kp="2000" ctrlrange="-1.2566370614359172 1.2566370614359172" forcerange="-200.0 200.0"/>
<position class="position" name="torso_2_joint_position" joint="torso_2_joint" kp="500" ctrlrange="-0.22689280275926285 0.7330382858376184" forcerange="-200.0 200.0"/>
<position class="position" name="head_1_joint_position" joint="head_1_joint" kp="200" ctrlrange="-0.20943951023931956 0.7853981633974483" forcerange="-8.0 8.0"/>
<position class="position" name="head_2_joint_position" joint="head_2_joint" kp="1000" ctrlrange="-1.3089969389957472 1.3089969389957472" forcerange="-4.0 4.0"/>
<position class="position" name="arm_left_1_joint_position" joint="arm_left_1_joint" kp="100" ctrlrange="-1.5707963267948966 0.7853981633974483" forcerange="-100.0 100.0"/>
<position class="position" name="arm_left_2_joint_position" joint="arm_left_2_joint" kp="100" ctrlrange="0.008726646259971648 2.871066619530672" forcerange="-100.0 100.0"/>
<position class="position" name="arm_left_3_joint_position" joint="arm_left_3_joint" kp="100" ctrlrange="-2.426007660272118 2.426007660272118" forcerange="-70.0 70.0"/>
<position class="position" name="arm_left_4_joint_position" joint="arm_left_4_joint" kp="100" ctrlrange="-2.234021442552742 -0.003490658503988659" forcerange="-70.0 70.0"/>
<position class="position" name="arm_left_5_joint_position" joint="arm_left_5_joint" kp="100" ctrlrange="-2.5132741228718345 2.5132741228718345" forcerange="-20.0 20.0"/>
<position class="position" name="arm_left_6_joint_position" joint="arm_left_6_joint" kp="100" ctrlrange="-1.3700834628155487 1.3700834628155487" forcerange="-8.0 8.0"/>
<position class="position" name="arm_left_7_joint_position" joint="arm_left_7_joint" kp="100" ctrlrange="-0.6806784082777885 0.6806784082777885" forcerange="-8.0 8.0"/>
<position class="position" name="gripper_left_joint_position" joint="gripper_left_joint" kp="1000" ctrlrange="-0.9599310885968813 0.0" forcerange="-10.0 10.0"/>
<position class="position" name="arm_right_1_joint_position" joint="arm_right_1_joint" kp="100" ctrlrange="-0.7853981633974483 1.5707963267948966" forcerange="-100.0 100.0"/>
<position class="position" name="arm_right_2_joint_position" joint="arm_right_2_joint" kp="100" ctrlrange="-2.871066619530672 -0.008726646259971648" forcerange="-100.0 100.0"/>
<position class="position" name="arm_right_3_joint_position" joint="arm_right_3_joint" kp="100" ctrlrange="-2.426007660272118 2.426007660272118" forcerange="-70.0 70.0"/>
<position class="position" name="arm_right_4_joint_position" joint="arm_right_4_joint" kp="100" ctrlrange="-2.234021442552742 -0.003490658503988659" forcerange="-70.0 70.0"/>
<position class="position" name="arm_right_5_joint_position" joint="arm_right_5_joint" kp="100" ctrlrange="-2.5132741228718345 2.5132741228718345" forcerange="-20.0 20.0"/>
<position class="position" name="arm_right_6_joint_position" joint="arm_right_6_joint" kp="100" ctrlrange="-1.3700834628155487 1.3700834628155487" forcerange="-8.0 8.0"/>
<position class="position" name="arm_right_7_joint_position" joint="arm_right_7_joint" kp="100" ctrlrange="-0.6806784082777885 0.6806784082777885" forcerange="-8.0 8.0"/>
<position class="position" name="gripper_right_joint_position" joint="gripper_right_joint" kp="1000" ctrlrange="-0.9599310885968813 0.0" forcerange="-10.0 10.0"/>
<position class="position" name="leg_left_1_joint_position" joint="leg_left_1_joint" kp="1000" ctrlrange="-0.3490658503988659 1.5707963267948966" forcerange="-100 100"/>
<position class="position" name="leg_left_2_joint_position" joint="leg_left_2_joint" kp="1000" ctrlrange="-0.5236 0.5236" forcerange="-160 160"/>
<position class="position" name="leg_left_3_joint_position" joint="leg_left_3_joint" kp="1000" ctrlrange="-2.095 0.7" forcerange="-160 160"/>
<position class="position" name="leg_left_4_joint_position" joint="leg_left_4_joint" kp="1000" ctrlrange="0 2.618" forcerange="-400 400"/>
<position class="position" name="leg_left_5_joint_position" joint="leg_left_5_joint" kp="10000" ctrlrange="-1.27 0.68" forcerange="-160 160"/>
<position class="position" name="leg_left_6_joint_position" joint="leg_left_6_joint" kp="10000" ctrlrange="-0.5236 0.5236" forcerange="-100 100"/>
<position class="position" name="leg_right_1_joint_position" joint="leg_right_1_joint" kp="1000" ctrlrange="-1.5707963267948966 0.3490658503988659" forcerange="-100 100"/>
<position class="position" name="leg_right_2_joint_position" joint="leg_right_2_joint" kp="1000" ctrlrange="-0.5236 0.5236" forcerange="-160 160"/>
<position class="position" name="leg_right_3_joint_position" joint="leg_right_3_joint" kp="1000" ctrlrange="-2.095 0.7" forcerange="-160 160"/>
<position class="position" name="leg_right_4_joint_position" joint="leg_right_4_joint" kp="1000" ctrlrange="0 2.618" forcerange="-400 400"/>
<position class="position" name="leg_right_5_joint_position" joint="leg_right_5_joint" kp="10000" ctrlrange="-1.27 0.68" forcerange="-160 160"/>
<position class="position" name="leg_right_6_joint_position" joint="leg_right_6_joint" kp="10000" ctrlrange="-0.5236 0.5236" forcerange="-100 100"/>
<position class="position" name="torso_1_joint_position" joint="torso_1_joint" kp="2000"
ctrlrange="-1.2566370614359172 1.2566370614359172" forcerange="-200.0 200.0"/>
<position class="position" name="torso_2_joint_position" joint="torso_2_joint" kp="500"
ctrlrange="-0.22689280275926285 0.7330382858376184" forcerange="-200.0 200.0"/>
<position class="position" name="head_1_joint_position" joint="head_1_joint" kp="200"
ctrlrange="-0.20943951023931956 0.7853981633974483" forcerange="-8.0 8.0"/>
<position class="position" name="head_2_joint_position" joint="head_2_joint" kp="1000"
ctrlrange="-1.3089969389957472 1.3089969389957472" forcerange="-4.0 4.0"/>
<position class="position" name="arm_left_1_joint_position" joint="arm_left_1_joint" kp="100"
ctrlrange="-1.5707963267948966 0.7853981633974483" forcerange="-100.0 100.0"/>
<position class="position" name="arm_left_2_joint_position" joint="arm_left_2_joint" kp="100"
ctrlrange="0.008726646259971648 2.871066619530672" forcerange="-100.0 100.0"/>
<position class="position" name="arm_left_3_joint_position" joint="arm_left_3_joint" kp="100"
ctrlrange="-2.426007660272118 2.426007660272118" forcerange="-70.0 70.0"/>
<position class="position" name="arm_left_4_joint_position" joint="arm_left_4_joint" kp="100"
ctrlrange="-2.234021442552742 -0.003490658503988659" forcerange="-70.0 70.0"/>
<position class="position" name="arm_left_5_joint_position" joint="arm_left_5_joint" kp="100"
ctrlrange="-2.5132741228718345 2.5132741228718345" forcerange="-20.0 20.0"/>
<position class="position" name="arm_left_6_joint_position" joint="arm_left_6_joint" kp="100"
ctrlrange="-1.3700834628155487 1.3700834628155487" forcerange="-8.0 8.0"/>
<position class="position" name="arm_left_7_joint_position" joint="arm_left_7_joint" kp="100"
ctrlrange="-0.6806784082777885 0.6806784082777885" forcerange="-8.0 8.0"/>
<position class="position" name="gripper_left_joint_position" joint="gripper_left_joint" kp="1000"
ctrlrange="-0.9599310885968813 0.0" forcerange="-10.0 10.0"/>
<position class="position" name="arm_right_1_joint_position" joint="arm_right_1_joint" kp="100"
ctrlrange="-0.7853981633974483 1.5707963267948966" forcerange="-100.0 100.0"/>
<position class="position" name="arm_right_2_joint_position" joint="arm_right_2_joint" kp="100"
ctrlrange="-2.871066619530672 -0.008726646259971648" forcerange="-100.0 100.0"/>
<position class="position" name="arm_right_3_joint_position" joint="arm_right_3_joint" kp="100"
ctrlrange="-2.426007660272118 2.426007660272118" forcerange="-70.0 70.0"/>
<position class="position" name="arm_right_4_joint_position" joint="arm_right_4_joint" kp="100"
ctrlrange="-2.234021442552742 -0.003490658503988659" forcerange="-70.0 70.0"/>
<position class="position" name="arm_right_5_joint_position" joint="arm_right_5_joint" kp="100"
ctrlrange="-2.5132741228718345 2.5132741228718345" forcerange="-20.0 20.0"/>
<position class="position" name="arm_right_6_joint_position" joint="arm_right_6_joint" kp="100"
ctrlrange="-1.3700834628155487 1.3700834628155487" forcerange="-8.0 8.0"/>
<position class="position" name="arm_right_7_joint_position" joint="arm_right_7_joint" kp="100"
ctrlrange="-0.6806784082777885 0.6806784082777885" forcerange="-8.0 8.0"/>
<position class="position" name="gripper_right_joint_position" joint="gripper_right_joint" kp="1000"
ctrlrange="-0.9599310885968813 0.0" forcerange="-10.0 10.0"/>
<position class="position" name="leg_left_1_joint_position" joint="leg_left_1_joint" kp="1000"
ctrlrange="-0.3490658503988659 1.5707963267948966" forcerange="-100 100"/>
<position class="position" name="leg_left_2_joint_position" joint="leg_left_2_joint" kp="1000"
ctrlrange="-0.5236 0.5236" forcerange="-160 160"/>
<position class="position" name="leg_left_3_joint_position" joint="leg_left_3_joint" kp="1000"
ctrlrange="-2.095 0.7" forcerange="-160 160"/>
<position class="position" name="leg_left_4_joint_position" joint="leg_left_4_joint" kp="1000" ctrlrange="0 2.618"
forcerange="-400 400"/>
<position class="position" name="leg_left_5_joint_position" joint="leg_left_5_joint" kp="10000"
ctrlrange="-1.27 0.68" forcerange="-160 160"/>
<position class="position" name="leg_left_6_joint_position" joint="leg_left_6_joint" kp="10000"
ctrlrange="-0.5236 0.5236" forcerange="-100 100"/>
<position class="position" name="leg_right_1_joint_position" joint="leg_right_1_joint" kp="1000"
ctrlrange="-1.5707963267948966 0.3490658503988659" forcerange="-100 100"/>
<position class="position" name="leg_right_2_joint_position" joint="leg_right_2_joint" kp="1000"
ctrlrange="-0.5236 0.5236" forcerange="-160 160"/>
<position class="position" name="leg_right_3_joint_position" joint="leg_right_3_joint" kp="1000"
ctrlrange="-2.095 0.7" forcerange="-160 160"/>
<position class="position" name="leg_right_4_joint_position" joint="leg_right_4_joint" kp="1000" ctrlrange="0 2.618"
forcerange="-400 400"/>
<position class="position" name="leg_right_5_joint_position" joint="leg_right_5_joint" kp="10000"
ctrlrange="-1.27 0.68" forcerange="-160 160"/>
<position class="position" name="leg_right_6_joint_position" joint="leg_right_6_joint" kp="10000"
ctrlrange="-0.5236 0.5236" forcerange="-100 100"/>
</actuator>

<keyframe>
Expand Down

0 comments on commit b9336e2

Please sign in to comment.