|
1 | 1 | <mujoco model="low_cost_robot_arm"> |
2 | | - <compiler angle="radian" meshdir="./assets/"/> |
| 2 | + <compiler angle="radian" meshdir="assets"/> |
3 | 3 |
|
4 | | - <option cone="elliptic" impratio="10"/> |
| 4 | + <option integrator="implicitfast" cone="elliptic" impratio="10"/> |
5 | 5 |
|
6 | 6 | <default> |
7 | 7 | <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"/> |
10 | 10 | <default class="visual"> |
11 | 11 | <geom type="mesh" group="2" contype="0" conaffinity="0"/> |
12 | 12 | </default> |
13 | 13 | <default class="collision"> |
14 | 14 | <geom type="mesh" group="3" mass="0" density="0"/> |
15 | 15 | <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"/> |
17 | 18 | </default> |
18 | 19 | <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"/> |
20 | 22 | </default> |
21 | 23 | </default> |
22 | 24 | </default> |
23 | 25 | </default> |
24 | 26 |
|
25 | 27 | <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"/> |
28 | 30 |
|
29 | 31 | <mesh name="base_link" file="base_link.stl"/> |
30 | 32 | <mesh name="shoulder_rotation" file="shoulder_rotation.stl"/> |
|
33 | 35 | <mesh name="elbow_to_wrist" file="elbow_to_wrist.stl"/> |
34 | 36 | <mesh name="gripper_static_finger" file="gripper_static_finger.stl"/> |
35 | 37 | <mesh name="gripper_moving_finger" file="gripper_moving_finger.stl"/> |
36 | | - |
37 | 38 | <mesh name="base_link_motor" file="base_link_motor.stl"/> |
38 | 39 | <mesh name="shoulder_rotation_motor" file="shoulder_rotation_motor.stl"/> |
39 | 40 | <mesh name="shoulder_to_elbow_motor" file="shoulder_to_elbow_motor.stl"/> |
40 | 41 | <mesh name="elbow_to_wrist_extension_motor" file="elbow_to_wrist_extension_motor.stl"/> |
41 | 42 | <mesh name="elbow_to_wrist_motor" file="elbow_to_wrist_motor.stl"/> |
42 | 43 | <mesh name="gripper_static_finger_motor" file="gripper_static_finger_motor.stl"/> |
43 | | - |
44 | 44 | <mesh name="base_link_collision" file="base_link_collision.stl"/> |
45 | 45 | <mesh name="shoulder_rotation_collision" file="shoulder_rotation_collision.stl"/> |
46 | 46 | <mesh name="shoulder_to_elbow_collision" file="shoulder_to_elbow_collision.stl"/> |
|
50 | 50 | <mesh name="gripper_static_finger_collision_2" file="gripper_static_finger_collision_2.stl"/> |
51 | 51 | <mesh name="gripper_moving_finger_collision_1" file="gripper_moving_finger_collision_1.stl"/> |
52 | 52 | <mesh name="gripper_moving_finger_collision_2" file="gripper_moving_finger_collision_2.stl"/> |
53 | | - |
54 | 53 | </asset> |
55 | 54 |
|
56 | 55 | <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"> |
58 | 57 | <geom mesh="base_link" class="visual" material="white"/> |
59 | 58 | <geom mesh="base_link_motor" class="visual" material="black"/> |
60 | 59 | <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"/> |
64 | 63 | <joint name="base_rotation" pos="0 0 0" axis="0 0 -1" range="-2.2 2.2"/> |
65 | 64 | <geom mesh="shoulder_rotation" class="visual" material="white"/> |
66 | 65 | <geom mesh="shoulder_rotation_motor" class="visual" material="black"/> |
67 | 66 | <geom mesh="shoulder_rotation_collision" class="collision"/> |
68 | | - |
69 | 67 | <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"/> |
71 | 70 | <joint name="pitch" pos="0 0 0" axis="0 1 0" range="-1.57 0.6"/> |
72 | 71 | <geom mesh="shoulder_to_elbow" class="visual" material="white"/> |
73 | 72 | <geom mesh="shoulder_to_elbow_motor" class="visual" material="black"/> |
74 | 73 | <geom mesh="shoulder_to_elbow_collision" class="collision"/> |
75 | | - |
76 | 74 | <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"/> |
78 | 77 | <joint name="elbow" pos="0 0 0" axis="0 -1 0" range="-1.57 1.45"/> |
79 | 78 | <geom mesh="elbow_to_wrist_extension" class="visual" material="white"/> |
80 | 79 | <geom mesh="elbow_to_wrist_extension_motor" class="visual" material="black"/> |
81 | 80 | <geom mesh="elbow_to_wrist_extension_collision" class="collision"/> |
82 | | - |
83 | 81 | <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"/> |
85 | 84 | <joint name="wrist_pitch" pos="0 0 0" axis="0 1 0" range="-2.0 2.0"/> |
86 | 85 | <geom mesh="elbow_to_wrist" class="visual" material="white"/> |
87 | 86 | <geom mesh="elbow_to_wrist_motor" class="visual" material="black"/> |
88 | 87 | <geom mesh="elbow_to_wrist_collision" class="collision"/> |
89 | | - |
90 | 88 | <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"/> |
92 | 91 | <joint name="wrist_roll" pos="0 0 0" axis="1 0 0" range="-3.14 3.14"/> |
93 | 92 | <geom mesh="gripper_static_finger" class="visual" material="white"/> |
94 | 93 | <geom mesh="gripper_static_finger_motor" class="visual" material="black"/> |
95 | 94 | <geom mesh="gripper_static_finger_collision_1" class="collision"/> |
96 | 95 | <geom mesh="gripper_static_finger_collision_2" class="collision"/> |
97 | | - |
98 | 96 | <geom class="pad_box1" name="gripper_static_finger_pad_1" pos="-0.0668 0.0105 0.00045"/> |
99 | 97 | <geom class="pad_box2" name="gripper_static_finger_pad_3" pos="-0.0628 0.0105 0.0005"/> |
100 | | - |
101 | 98 | <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"/> |
103 | 101 | <joint name="gripper" pos="0 0 0" axis="0 0 -1" range="-1.60 0.032" frictionloss="0.1"/> |
104 | 102 | <geom mesh="gripper_moving_finger" class="visual" material="white"/> |
105 | 103 | <geom mesh="gripper_moving_finger_collision_1" class="collision"/> |
106 | 104 | <geom mesh="gripper_moving_finger_collision_2" class="collision"/> |
107 | | - |
108 | 105 | <geom class="pad_box1" name="gripper_moving_finger_pad_1" pos="-0.0535 0.0113 -0.01395"/> |
109 | 106 | <geom class="pad_box2" name="gripper_moving_finger_pad_3" pos="-0.0495 0.0113 -0.01395"/> |
110 | 107 | </body> |
|
121 | 118 | </contact> |
122 | 119 |
|
123 | 120 | <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"/> |
130 | 127 | </actuator> |
131 | 128 |
|
132 | 129 | <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"/> |
134 | 131 | </keyframe> |
135 | | - |
136 | 132 | </mujoco> |
0 commit comments