Skip to content

Commit 2122b91

Browse files
committed
refactor low_cost_robot_arm XML files
1 parent 4caaf29 commit 2122b91

File tree

2 files changed

+32
-37
lines changed

2 files changed

+32
-37
lines changed
Lines changed: 31 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -1,30 +1,32 @@
11
<mujoco model="low_cost_robot_arm">
2-
<compiler angle="radian" meshdir="./assets/"/>
2+
<compiler angle="radian" meshdir="assets"/>
33

4-
<option cone="elliptic" impratio="10"/>
4+
<option integrator="implicitfast" cone="elliptic" impratio="10"/>
55

66
<default>
77
<default class="low_cost_robot_arm">
8-
<joint armature="0.5" damping="1.5" stiffness="0" frictionloss="0.2"/>
9-
<position kp="100" kv="10" inheritrange="1"/>
8+
<joint armature="0.5" frictionloss="0.2"/>
9+
<position kp="100" kv="10" forcerange="-87 87" inheritrange="1"/>
1010
<default class="visual">
1111
<geom type="mesh" group="2" contype="0" conaffinity="0"/>
1212
</default>
1313
<default class="collision">
1414
<geom type="mesh" group="3" mass="0" density="0"/>
1515
<default class="pad_box1">
16-
<geom type="box" friction="0.7" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.002 0.002 0.0025" rgba="0.2 0.2 0.2 1"/>
16+
<geom type="box" friction="0.7" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1"
17+
size="0.002 0.002 0.0025" rgba="0.2 0.2 0.2 1"/>
1718
</default>
1819
<default class="pad_box2">
19-
<geom type="box" friction="0.6" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.002 0.002 0.0052" rgba="0.1 0.1 0.1 1"/>
20+
<geom type="box" friction="0.6" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1"
21+
size="0.002 0.002 0.0052" rgba="0.1 0.1 0.1 1"/>
2022
</default>
2123
</default>
2224
</default>
2325
</default>
2426

2527
<asset>
26-
<material name="black" rgba="0.1 0.1 0.1 1" specular="0.1" shininess="0.1"/>
27-
<material name="white" rgba="0.8 0.8 0.8 1" specular="0.1" shininess="0.1"/>
28+
<material name="black" rgba="0.1 0.1 0.1 1"/>
29+
<material name="white" rgba="0.8 0.8 0.8 1"/>
2830

2931
<mesh name="base_link" file="base_link.stl"/>
3032
<mesh name="shoulder_rotation" file="shoulder_rotation.stl"/>
@@ -33,14 +35,12 @@
3335
<mesh name="elbow_to_wrist" file="elbow_to_wrist.stl"/>
3436
<mesh name="gripper_static_finger" file="gripper_static_finger.stl"/>
3537
<mesh name="gripper_moving_finger" file="gripper_moving_finger.stl"/>
36-
3738
<mesh name="base_link_motor" file="base_link_motor.stl"/>
3839
<mesh name="shoulder_rotation_motor" file="shoulder_rotation_motor.stl"/>
3940
<mesh name="shoulder_to_elbow_motor" file="shoulder_to_elbow_motor.stl"/>
4041
<mesh name="elbow_to_wrist_extension_motor" file="elbow_to_wrist_extension_motor.stl"/>
4142
<mesh name="elbow_to_wrist_motor" file="elbow_to_wrist_motor.stl"/>
4243
<mesh name="gripper_static_finger_motor" file="gripper_static_finger_motor.stl"/>
43-
4444
<mesh name="base_link_collision" file="base_link_collision.stl"/>
4545
<mesh name="shoulder_rotation_collision" file="shoulder_rotation_collision.stl"/>
4646
<mesh name="shoulder_to_elbow_collision" file="shoulder_to_elbow_collision.stl"/>
@@ -50,61 +50,58 @@
5050
<mesh name="gripper_static_finger_collision_2" file="gripper_static_finger_collision_2.stl"/>
5151
<mesh name="gripper_moving_finger_collision_1" file="gripper_moving_finger_collision_1.stl"/>
5252
<mesh name="gripper_moving_finger_collision_2" file="gripper_moving_finger_collision_2.stl"/>
53-
5453
</asset>
5554

5655
<worldbody>
57-
<body name="base_link" childclass="low_cost_robot_arm" quat="-0.707 0. 0. 0.707">
56+
<body name="base_link" childclass="low_cost_robot_arm">
5857
<geom mesh="base_link" class="visual" material="white"/>
5958
<geom mesh="base_link_motor" class="visual" material="black"/>
6059
<geom mesh="base_link_collision" class="collision"/>
61-
62-
<body name="shoulder_rotation" pos="0.012 0 0.0409" >
63-
<inertial pos="0.011924 -0.00048792 0.013381" quat="-0.0190903 0.705417 0.0178052 0.708312" mass="0.05014" diaginertia="1.44921e-05 1.2371e-05 7.59138e-06"/>
60+
<body name="shoulder_rotation" pos="0.012 0 0.0409">
61+
<inertial pos="0.011924 -0.00048792 0.013381" quat="-0.0190903 0.705417 0.0178052 0.708312" mass="0.05014"
62+
diaginertia="1.44921e-05 1.2371e-05 7.59138e-06"/>
6463
<joint name="base_rotation" pos="0 0 0" axis="0 0 -1" range="-2.2 2.2"/>
6564
<geom mesh="shoulder_rotation" class="visual" material="white"/>
6665
<geom mesh="shoulder_rotation_motor" class="visual" material="black"/>
6766
<geom mesh="shoulder_rotation_collision" class="collision"/>
68-
6967
<body name="shoulder_to_elbow" pos="0 -0.0209 0.0154">
70-
<inertial pos="0.0011747 0.02097 0.071547" quat="0.998768 2.01447e-05 0.0496266 0.000367169" mass="0.050177" diaginertia="3.73065e-05 3.3772e-05 7.94901e-06"/>
68+
<inertial pos="0.0011747 0.02097 0.071547" quat="0.998768 2.01447e-05 0.0496266 0.000367169" mass="0.050177"
69+
diaginertia="3.73065e-05 3.3772e-05 7.94901e-06"/>
7170
<joint name="pitch" pos="0 0 0" axis="0 1 0" range="-1.57 0.6"/>
7271
<geom mesh="shoulder_to_elbow" class="visual" material="white"/>
7372
<geom mesh="shoulder_to_elbow_motor" class="visual" material="black"/>
7473
<geom mesh="shoulder_to_elbow_collision" class="collision"/>
75-
7674
<body name="elbow_to_wrist_extension" pos="-0.0148 0.0065 0.1083">
77-
<inertial pos="-0.05537 0.014505 0.0028659" quat="8.17663e-05 0.710999 -4.16983e-05 0.703193" mass="0.06379" diaginertia="2.45081e-05 2.2231e-05 7.34061e-06"/>
75+
<inertial pos="-0.05537 0.014505 0.0028659" quat="8.17663e-05 0.710999 -4.16983e-05 0.703193" mass="0.06379"
76+
diaginertia="2.45081e-05 2.2231e-05 7.34061e-06"/>
7877
<joint name="elbow" pos="0 0 0" axis="0 -1 0" range="-1.57 1.45"/>
7978
<geom mesh="elbow_to_wrist_extension" class="visual" material="white"/>
8079
<geom mesh="elbow_to_wrist_extension_motor" class="visual" material="black"/>
8180
<geom mesh="elbow_to_wrist_extension_collision" class="collision"/>
82-
8381
<body name="elbow_to_wrist" pos="-0.10048 5e-05 0.0026999">
84-
<inertial pos="-0.02652 0.019195 -9.0614e-06" quat="0.707361 0.706812 0.00580344 0.00484124" mass="0.019805" diaginertia="2.95813e-06 2.8759e-06 1.07787e-06"/>
82+
<inertial pos="-0.02652 0.019195 -9.0614e-06" quat="0.707361 0.706812 0.00580344 0.00484124"
83+
mass="0.019805" diaginertia="2.95813e-06 2.8759e-06 1.07787e-06"/>
8584
<joint name="wrist_pitch" pos="0 0 0" axis="0 1 0" range="-2.0 2.0"/>
8685
<geom mesh="elbow_to_wrist" class="visual" material="white"/>
8786
<geom mesh="elbow_to_wrist_motor" class="visual" material="black"/>
8887
<geom mesh="elbow_to_wrist_collision" class="collision"/>
89-
9088
<body name="gripper_static_finger" pos="-0.045 0.013097 0">
91-
<inertial pos="-0.019091 0.0053379 0.00018011" quat="0.105295 0.703509 -0.0986543 0.695885" mass="0.029277" diaginertia="8.11303e-06 7.14908e-06 3.27429e-06"/>
89+
<inertial pos="-0.019091 0.0053379 0.00018011" quat="0.105295 0.703509 -0.0986543 0.695885"
90+
mass="0.029277" diaginertia="8.11303e-06 7.14908e-06 3.27429e-06"/>
9291
<joint name="wrist_roll" pos="0 0 0" axis="1 0 0" range="-3.14 3.14"/>
9392
<geom mesh="gripper_static_finger" class="visual" material="white"/>
9493
<geom mesh="gripper_static_finger_motor" class="visual" material="black"/>
9594
<geom mesh="gripper_static_finger_collision_1" class="collision"/>
9695
<geom mesh="gripper_static_finger_collision_2" class="collision"/>
97-
9896
<geom class="pad_box1" name="gripper_static_finger_pad_1" pos="-0.0668 0.0105 0.00045"/>
9997
<geom class="pad_box2" name="gripper_static_finger_pad_3" pos="-0.0628 0.0105 0.0005"/>
100-
10198
<body name="gripper_moving_finger" pos="-0.01315 -0.0075 0.0145">
102-
<inertial pos="-0.02507 0.0010817 -0.01414" quat="0.528148 0.5474 0.466496 0.451436" mass="0.012831" diaginertia="3.49922e-06 2.45768e-06 1.4645e-06"/>
99+
<inertial pos="-0.02507 0.0010817 -0.01414" quat="0.528148 0.5474 0.466496 0.451436" mass="0.012831"
100+
diaginertia="3.49922e-06 2.45768e-06 1.4645e-06"/>
103101
<joint name="gripper" pos="0 0 0" axis="0 0 -1" range="-1.60 0.032" frictionloss="0.1"/>
104102
<geom mesh="gripper_moving_finger" class="visual" material="white"/>
105103
<geom mesh="gripper_moving_finger_collision_1" class="collision"/>
106104
<geom mesh="gripper_moving_finger_collision_2" class="collision"/>
107-
108105
<geom class="pad_box1" name="gripper_moving_finger_pad_1" pos="-0.0535 0.0113 -0.01395"/>
109106
<geom class="pad_box2" name="gripper_moving_finger_pad_3" pos="-0.0495 0.0113 -0.01395"/>
110107
</body>
@@ -121,16 +118,15 @@
121118
</contact>
122119

123120
<actuator>
124-
<position class="low_cost_robot_arm" name="base_rotation" joint="base_rotation" forcerange="-87 87"/>
125-
<position class="low_cost_robot_arm" name="pitch" joint="pitch" forcerange="-87 87"/>
126-
<position class="low_cost_robot_arm" name="elbow" joint="elbow" forcerange="-87 87"/>
127-
<position class="low_cost_robot_arm" name="wrist_pitch" joint="wrist_pitch" forcerange="-12 12"/>
128-
<position class="low_cost_robot_arm" name="wrist_roll" joint="wrist_roll" forcerange="-10 10"/>
129-
<position class="low_cost_robot_arm" name="gripper" joint="gripper" forcerange="-5 5"/>
121+
<position class="low_cost_robot_arm" name="base_rotation" joint="base_rotation" forcerange="-87 87"/>
122+
<position class="low_cost_robot_arm" name="pitch" joint="pitch" forcerange="-87 87"/>
123+
<position class="low_cost_robot_arm" name="elbow" joint="elbow" forcerange="-87 87"/>
124+
<position class="low_cost_robot_arm" name="wrist_pitch" joint="wrist_pitch" forcerange="-12 12"/>
125+
<position class="low_cost_robot_arm" name="wrist_roll" joint="wrist_roll" forcerange="-10 10"/>
126+
<position class="low_cost_robot_arm" name="gripper" joint="gripper" forcerange="-5 5"/>
130127
</actuator>
131128

132129
<keyframe>
133-
<key name="home" qpos="0 0 0 0 0 0"/>
130+
<key name="home" qpos="0 0 0 0 0 0" ctrl="0 0 0 0 0 0"/>
134131
</keyframe>
135-
136132
</mujoco>

low_cost_robot_arm/scene.xml

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,5 +20,4 @@
2020
<light pos="0 0 3" dir="0 0 -1" directional="false"/>
2121
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane" pos="0 0 0" friction="0.1"/>
2222
</worldbody>
23-
24-
</mujoco>
23+
</mujoco>

0 commit comments

Comments
 (0)