Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file added config/pam_mujoco/models/mesh/Base.stl
Binary file not shown.
Binary file added config/pam_mujoco/models/mesh/J1.stl
Binary file not shown.
Binary file added config/pam_mujoco/models/mesh/J2.stl
Binary file not shown.
Binary file added config/pam_mujoco/models/mesh/J3.stl
Binary file not shown.
Binary file added config/pam_mujoco/models/mesh/J4.stl
Binary file not shown.
114 changes: 61 additions & 53 deletions config/pam_mujoco/models/robot_templates/pamy2/body_template.xml

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
@@ -1,28 +1,31 @@
<robot>
<geom pos="0.0 0.0 0.0" name="?id?_frame" type="box" size="0.1 0.1 0.001" rgba=".35 .8 .4 1" solref="0.03 0.06"/>
<body name="?id?_arm">
<body>
<joint type="hinge" name="?id?_joint_base_rotation" axis="0 0 1" frictionloss="114.0189" solreffriction="0.5" solimpfriction="0.75294" limited="true" range="-89.8 89.8" solreflimit="0.003" solimplimit="1"/>
<geom type = "mesh" mesh="RL-50_Rotaryeinheit_abkupfer" rgba = "0.20 0.20 0.20 1" zaxis="-1 0 0" pos = "0.037 -0.037 0" mass="0.03"/>
<geom type = "mesh" mesh="RL-50_Rotaryeinheit_abkupfer" rgba = "0.20 0.20 0.20 1" xyaxes="0 0 1 0 -1 0" pos = "-0.0375 0.0375 0.0" mass="0.03"/>
<body pos = "0 0.0 0.075">
<geom name="?id?_dummy_cylinder_for_tendon_wrapping_2" type = "cylinder" pos="0 0.0 0.0" size="0.037 0.01" zaxis="0 1 0" rgba="1 0 0 0" mass="0.000001"/>
<joint type="hinge" name="?id?_dof2" axis="0 1 0" frictionloss="111.0899" solreffriction="0.075396" solimpfriction="0.65317" limited="true" range="-89.8 89.8" solreflimit="0.003" solimplimit="1"/>
<geom type = "mesh" mesh="igus_move" rgba = "0.20 0.20 0.20 1.0" zaxis="0 0 -1" pos = "-0.04 0.0366 0.065" mass="0.03"/>
<geom type = "cylinder" size="0.013 0.1425" pos="0 0 0.17262" zaxis="0 0 1" rgba="0.95 0.95 0.95 1.0" mass="0.14822"/>
<geom type = "mesh" mesh="igus_base_move" rgba = "0.20 0.20 0.20 1.0" pos="-0.036 -0.0325 0.411371" zaxis="0 1 0" mass="0.03"/>
<site name="?id?_center_joint_1_2" type="sphere" size=".04 0 0" rgba="1 0 1 0.2"/>
<body pos="0 0 0.36742">
<joint type="hinge" name="?id?_dof3" axis="0 1 0" frictionloss="7.7682" solreffriction="0.5" solimpfriction="0.65914" limited="true" range="-89.8 89.8" solreflimit="0.003" solimplimit="1"/>
<geom type = "mesh" mesh="igus_move" rgba = "0.20 0.20 0.20 1.0" zaxis="0 0 -1" pos = "-0.04 0.0366 0.065" mass="0.03"/>
<body pos="0 0 -0.395">
<joint type="hinge" name="?id?_dof4" axis="0 0 1" pos="0 0 0" frictionloss="111.9529" solreffriction="0.38711" solimpfriction="2.5699" limited="true" range="-89.8 89.8" solreflimit="0.003" solimplimit="1"/>
<geom type = "cylinder" size="0.013 0.105" pos="0 0 0.54" zaxis="0 0 1" rgba="0.95 0.95 0.95 1.0" mass="0.11402"/>
<geom name="?id?_racket_handle" type = "mesh" mesh="schlaeger_anbindung-igus_anbindung_extra-1" rgba="0.99 0.99 0.99 1" zaxis = "0 -1 0" pos ="-0.075 0.016 0.615" mass="0.02"/>
<geom name="?id?_racket" type = "mesh" mesh="schlaeger_anbindung-Tischtennisschlaeger_Butterfly-1" rgba="0.7 0.05 0.05 1" pos="-0.075 0.016 0.615" zaxis = "0 -1 0" mass="0.66342"/>
<site name="?id?_center_joint_3_4" pos="0 0 0.395" type="sphere" size=".04 0 0" rgba="1 0 1 0.2"/>
<!-- Base -->
<body name="?id?_arm">
<inertial pos="0.00014182603956811 -0.000217286489393455 -0.00245784885203652" mass="1.27071929199471" fullinertia="0.00567536540229646 0.00316590205030147 0.00872411416268657 -3.34745090158655E-05 9.94071247612805E-09 5.24827445642418E-08"/>
<geom name="?id?_frame" type="mesh" mesh="Base" rgba="0.898039215686275 0.917647058823529 0.929411764705882 1" mass="0"/>
<!-- J1 -->
<body pos="0 0 0.01" euler="180 0 0">
<joint type="hinge" name="?id?_joint_base_rotation" axis="0 0 -1" frictionloss="114.0189" solreffriction="0.5" solimpfriction="0.75294" limited="true" range="-85.0 85.0" solreflimit="0.003" solimplimit="1"/>
<inertial pos="0.000130781333923981 0.000395087107960899 -2.30204502387789E-05" mass="0.884595751651612" fullinertia="0.000957184766492343 0.000943127481202976 0.00166205903985012 7.26525656006142E-08 2.16679898461153E-07 -2.0945043536217E-07"/>
<geom type="mesh" mesh="J1" rgba="0.698039215686274 0.698039215686274 0.698039215686274 1" mass="0"/>
<!-- J2 -->
<body pos="0 0 -0.064" euler="180 0 180"> <!-- was: euler="180 0 -180"-->
<inertial pos="-0.00318822226425911 -0.00156350715458152 0.187131602669781" mass="0.747221805509099" fullinertia="0.00183751261065788 0.00194288763095422 0.000201104761524309 9.36914048087975E-07 2.8551485268662E-05 4.04806959268614E-06"/>
<geom type="mesh" mesh="J2" rgba="0.698039215686274 0.698039215686274 0.698039215686274 1" mass="0"/>
<joint type="hinge" name="?id?_dof2" axis="0 -1 0" frictionloss="111.0899" solreffriction="0.075396" solimpfriction="0.65317" limited="true" range="-85.0 85.0" solreflimit="0.003" solimplimit="1"/>
<!-- J3 -->
<body pos="0 0 0.39986" euler="180 0 180">
<joint type="hinge" name="?id?_dof3" axis="0 -1 0" frictionloss="7.7682" solreffriction="0.5" solimpfriction="0.65914" limited="true" range="-85.0 85.0" solreflimit="0.003" solimplimit="1"/>
<inertial pos="0.000476084514538831 -0.00627422416764544 -0.0180864211606709" mass="0.310581849393537" fullinertia="0.000170712877571993 0.00023028333846519 9.14283413127416E-05 6.39009188619916E-08 2.17211789062173E-06 -1.54349521030329E-06"/>
<geom type="mesh" mesh="J3" rgba="0.698039215686274 0.698039215686274 0.698039215686274 1" mass="0"/>
<!-- J4 -->
<body euler="180 0 0"> <!-- was: euler="-180 -1 0"-->
<joint type="hinge" name="?id?_dof4" axis="0 0 1" pos="0 0 0" frictionloss="27.7682" solreffriction="0.38711" solimpfriction="2.5699" limited="true" range="-85.0 85.0" solreflimit="0.003" solimplimit="1"/>
<geom type="mesh" mesh="J4" rgba="0.898039215686275 0.917647058823529 0.929411764705882 1" mass="0"/>
<inertial pos="-7.76532889874594E-05 0.000224318522056323 0.278462053726287" mass="0.538421831235413" fullinertia="0.00115973040414782 0.00165716877599009 0.000528448429186829 1.77245727732792E-08 1.36310388287712E-08 6.87618492418858E-08"/>
<geom name="?id?_racket" type = "mesh" mesh="schlaeger_anbindung-Tischtennisschlaeger_Butterfly-1" rgba="0.7 0.05 0.05 1" pos="-0.075 0.057 0.211" zaxis = "0 -1 0" mass="0.66342"/>
</body>
</body>
</body>
</body>
</body>
</body>
Expand Down
12 changes: 6 additions & 6 deletions config/pam_mujoco/models/robot_templates/tendon_template.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<geom geom="?id?_dummy_cylinder_for_tendon_wrapping_1"/>
<site site="?id?_tendon_1_base_rot_connection"/>
</spatial>
<spatial name = "?id?_tendon_3" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 0.88194" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<spatial name = "?id?_tendon_3" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 0.95594" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<site site="?id?_muscle_3_moving_end"/>
<site site="?id?_muscle_3_tendon_horizontal_point"/>
<site site="?id?_center_joint_1_2"/>
Expand All @@ -24,7 +24,7 @@
<geom geom="?id?_dummy_cylinder_for_tendon_wrapping_2"/>
<site site="?id?_tendon_4_base_rot_connection"/>
</spatial>
<spatial name = "?id?_tendon_4" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 0.95594" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<spatial name = "?id?_tendon_4" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 0.88194" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<site site="?id?_muscle_4_moving_end"/>
<site site="?id?_muscle_4_tendon_horizontal_point"/>
<site site="?id?_center_joint_1_2"/>
Expand All @@ -34,7 +34,7 @@
<geom geom="?id?_dummy_cylinder_for_tendon_wrapping_2"/>
<site site="?id?_tendon_3_base_rot_connection"/>
</spatial>
<spatial name = "?id?_tendon_5" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 1.293" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<spatial name = "?id?_tendon_5" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 1.467" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<site site="?id?_muscle_5_moving_end"/>
<site site="?id?_muscle_5_tendon_horizontal_point"/>
<site site="?id?_center_joint_1_2"/>
Expand All @@ -45,7 +45,7 @@
<geom geom="?id?_dummy_cylinder_for_tendon_wrapping_3"/>
<site site="?id?_tendon_6_base_rot_connection"/>
</spatial>
<spatial name = "?id?_tendon_6" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 1.367" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<spatial name = "?id?_tendon_6" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 1.393" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<site site="?id?_muscle_6_moving_end"/>
<site site="?id?_muscle_6_tendon_horizontal_point"/>
<site site="?id?_center_joint_1_2"/>
Expand All @@ -56,7 +56,7 @@
<geom geom="?id?_dummy_cylinder_for_tendon_wrapping_3"/>
<site site="?id?_tendon_5_base_rot_connection"/>
</spatial>
<spatial name = "?id?_tendon_7" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 1.3016" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<spatial name = "?id?_tendon_7" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 1.6356" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<site site="?id?_muscle_7_moving_end"/>
<site site="?id?_muscle_7_tendon_horizontal_point"/>
<site site="?id?_center_joint_1_2"/>
Expand All @@ -67,7 +67,7 @@
<geom geom="?id?_dummy_cylinder_for_tendon_wrapping_4"/>
<site site="?id?_tendon_8_base_rot_connection"/>
</spatial>
<spatial name = "?id?_tendon_8" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 1.3756" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<spatial name = "?id?_tendon_8" width="0.001" rgba="0.7 0.4 0.4 0.2" limited="true" range="0.0 1.5616" damping="418.6191" solreflimit="0.005" solimplimit="1" stiffness="218205.4346">
<site site="?id?_muscle_8_moving_end"/>
<site site="?id?_muscle_8_tendon_horizontal_point"/>
<site site="?id?_center_joint_1_2"/>
Expand Down
9 changes: 7 additions & 2 deletions config/pam_mujoco/models/template.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<mujoco>
<compiler coordinate="local" meshdir="$models_path$/igus/" angle="degree"/>
<compiler coordinate="local" meshdir="$models_path$/mesh/" angle="degree"/>
<size njmax="6000" nconmax="6000"/>
<option gravity="0 0 -9.81" integrator="RK4" timestep="$timestep$" density="1.2" collision="predefined">
<flag gravity="enable" contact="enable" passive="enable"/>
Expand All @@ -13,7 +13,12 @@
<mesh file="igus_base_move.stl" scale="0.001 0.001 0.001"/>
<mesh file="igus_move.stl" scale="0.001 0.001 0.001"/>
<mesh file="schlaeger_anbindung-igus_anbindung_extra-1.stl" scale="0.001 0.001 0.001"/>
<mesh file="schlaeger_anbindung-Tischtennisschlaeger_Butterfly-1.stl" scale="0.001 0.001 0.001"/>
<mesh file="schlaeger_anbindung-Tischtennisschlaeger_Butterfly-1.stl" scale="0.001 0.001 0.0035"/>
<mesh file="Base.stl" scale="1.0 1.0 1.0"/>
<mesh file="J1.stl" scale="1.0 1.0 1.0"/>
<mesh file="J2.stl" scale="1.0 1.0 1.0"/>
<mesh file="J3.stl" scale="1.0 1.0 1.0"/>
<mesh file="J4.stl" scale="1.0 1.0 1.0"/>
</asset>
<worldbody>
<light diffuse="1.5 1.5 1.5" pos="0 0 8.0" dir="0 0 -1"/>
Expand Down
Loading