Skip to content
Merged
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
198 changes: 198 additions & 0 deletions assets/fr3/mjcf/fr3_0.xml

Large diffs are not rendered by default.

42 changes: 0 additions & 42 deletions assets/fr3/mjcf/fr3_common.xml
Original file line number Diff line number Diff line change
@@ -1,49 +1,7 @@
<mujoco model="fr3">
<compiler angle="radian" meshdir="assets"/>

<option integrator="implicitfast" impratio="20" noslip_iterations="5" cone="elliptic"/>

<default>
<default class="fr3">
<joint armature="0.1" damping="1"/>
<position inheritrange="1"/>
<default class="finger">
<joint axis="0 1 0" type="slide" range="0 0.04"/>
</default>
<default class="visual">
<geom type="mesh" group="2" contype="0" conaffinity="0"/>
</default>
<default class="collision">
<geom type="mesh" group="3" mass="0" density="0"/>
<default class="fingertip_pad_collision_1">
<geom type="box" size="0.0085 0.004 0.0085" pos="0 0.0055 0.0445"/>
</default>
<default class="fingertip_pad_collision_2">
<geom type="box" size="0.003 0.002 0.003" pos="0.0055 0.002 0.05"/>
</default>
<default class="fingertip_pad_collision_3">
<geom type="box" size="0.003 0.002 0.003" pos="-0.0055 0.002 0.05"/>
</default>
<default class="fingertip_pad_collision_4">
<geom type="box" size="0.003 0.002 0.0035" pos="0.0055 0.002 0.0395"/>
</default>
<default class="fingertip_pad_collision_5">
<geom type="box" size="0.003 0.002 0.0035" pos="-0.0055 0.002 0.0395"/>
</default>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
</default>
<default class="d435i">
<material specular="0" shininess="0.25"/>
<default class="visual_d435i">
<geom group="2" type="mesh" contype="0" conaffinity="0" mass="0"/>
</default>
<default class="collision_d435i">
<geom group="3" type="mesh" mass="0"/>
</default>
</default>
</default>

<asset>
<material name="black" rgba=".2 .2 .2 1"/>
<material name="white" rgba="1 1 1 1"/>
Expand Down
60 changes: 53 additions & 7 deletions assets/fr3/mjcf/fr3_unnamed.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,50 @@
<mujoco>
<!-- custom tcp offset -->
<custom>
<numeric name="tcp_offset_translation" data="0.0 0.0 0.1034"/>
<!-- rotation matrix is row major -->
<numeric name="tcp_offset_rotation_matrix" data="0.707 0.707 0 -0.707 0.707 0 0 0 1"/>
</custom>
<default>
<default class="fr3">
<joint armature="0.1" damping="1"/>
<position inheritrange="1"/>
<default class="finger">
<joint axis="0 1 0" type="slide" range="0 0.04"/>
</default>
<default class="visual">
<geom type="mesh" group="2" contype="0" conaffinity="0"/>
</default>
<default class="collision">
<geom type="mesh" group="3" mass="0" density="0"/>
<default class="fingertip_pad_collision_1">
<geom type="box" size="0.0085 0.004 0.0085" pos="0 0.0055 0.0445"/>
</default>
<default class="fingertip_pad_collision_2">
<geom type="box" size="0.003 0.002 0.003" pos="0.0055 0.002 0.05"/>
</default>
<default class="fingertip_pad_collision_3">
<geom type="box" size="0.003 0.002 0.003" pos="-0.0055 0.002 0.05"/>
</default>
<default class="fingertip_pad_collision_4">
<geom type="box" size="0.003 0.002 0.0035" pos="0.0055 0.002 0.0395"/>
</default>
<default class="fingertip_pad_collision_5">
<geom type="box" size="0.003 0.002 0.0035" pos="-0.0055 0.002 0.0395"/>
</default>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
</default>
<default class="d435i">
<material specular="0" shininess="0.25"/>
<default class="visual_d435i">
<geom group="2" type="mesh" contype="0" conaffinity="0" mass="0"/>
</default>
<default class="collision_d435i">
<geom group="3" type="mesh" mass="0"/>
</default>
</default>
</default>
<worldbody>
<body name="base" childclass="fr3" gravcomp="1">
<body name="fr3_link0" gravcomp="1">
Expand All @@ -13,41 +59,41 @@
<body name="fr3_link1" pos="0 0 0.333" gravcomp="1">
<inertial pos="4.128e-07 -0.0181251 -0.0386036" quat="0.999901 0.0021545 0.00429041 0.0132325" mass="2.92747"
diaginertia="0.0186043 0.0181194 0.00538716"/>
<joint name="fr3_joint1" axis="0 0 1" range="-2.7437 2.7437" actuatorfrcrange="-87 87"/>
<joint name="fr3_joint1" axis="0 0 1" range="-2.7437 2.7437" actuatorfrcrange="-87 87" actuatorgravcomp="true"/>
<geom name="fr3_link1_collision" class="collision" mesh="fr3_link1_coll"/>
<geom material="white" mesh="fr3_link1" class="visual"/>
<body name="fr3_link2" quat="1 -1 0 0" gravcomp="1">
<inertial pos="0.00318289 -0.0743222 0.00881461" quat="0.356855 0.680818 -0.434812 0.469126" mass="2.93554"
diaginertia="0.0299291 0.0299291 0.0299291"/>
<joint name="fr3_joint2" axis="0 0 1" range="-1.7837 1.7837" actuatorfrcrange="-87 87"/>
<joint name="fr3_joint2" axis="0 0 1" range="-1.7837 1.7837" actuatorfrcrange="-87 87" actuatorgravcomp="true"/>
<geom material="white" mesh="fr3_link2" class="visual"/>
<geom name="fr3_link2_collision" class="collision" mesh="fr3_link2_coll"/>
<body name="fr3_link3" pos="0 -0.316 0" quat="1 1 0 0" gravcomp="1">
<inertial pos="0.0407016 -0.00482006 -0.0289731" quat="0.950032 -0.148357 0.229935 0.150201" mass="2.2449"
diaginertia="0.0140109 0.0140109 0.0140109"/>
<joint name="fr3_joint3" axis="0 0 1" range="-2.9007 2.9007" actuatorfrcrange="-87 87"/>
<joint name="fr3_joint3" axis="0 0 1" range="-2.9007 2.9007" actuatorfrcrange="-87 87" actuatorgravcomp="true"/>
<geom mesh="fr3_link3_0" material="white" class="visual"/>
<geom mesh="fr3_link3_1" material="black" class="visual"/>
<geom name="fr3_link3_collision" class="collision" mesh="fr3_link3_coll"/>
<body name="fr3_link4" pos="0.0825 0 0" quat="1 1 0 0" gravcomp="1">
<inertial pos="-0.0459101 0.0630493 -0.00851879" quat="0.23761 0.892458 -0.00078702 0.383484"
mass="2.6156" diaginertia="0.0206104 0.0206104 0.0206104"/>
<joint name="fr3_joint4" axis="0 0 1" range="-3.0421 -0.1518" actuatorfrcrange="-87 87"/>
<joint name="fr3_joint4" axis="0 0 1" range="-3.0421 -0.1518" actuatorfrcrange="-87 87" actuatorgravcomp="true"/>
<geom mesh="fr3_link4_0" material="white" class="visual"/>
<geom mesh="fr3_link4_1" material="black" class="visual"/>
<geom name="fr3_link4_collision" class="collision" mesh="fr3_link4_coll"/>
<body name="fr3_link5" pos="-0.0825 0.384 0" quat="1 -1 0 0" gravcomp="1">
<inertial pos="-0.00160396 0.0292536 -0.0972966" quat="0.922285 0.098826 0.0982562 -0.360514"
mass="2.32712" diaginertia="0.0182879 0.0182879 0.0182879"/>
<joint name="fr3_joint5" axis="0 0 1" range="-2.8065 2.8065" actuatorfrcrange="-12 12"/>
<joint name="fr3_joint5" axis="0 0 1" range="-2.8065 2.8065" actuatorfrcrange="-12 12" actuatorgravcomp="true"/>
<geom mesh="fr3_link5_0" material="white" class="visual"/>
<geom mesh="fr3_link5_1" material="white" class="visual"/>
<geom mesh="fr3_link5_2" material="black" class="visual"/>
<geom name="fr3_link5_collision" class="collision" mesh="fr3_link5_coll"/>
<body name="fr3_link6" quat="1 1 0 0" gravcomp="1">
<inertial pos="0.0597131 -0.0410295 -0.0101693" quat="0.593933 0.525442 0.520644 0.316361"
mass="1.81704" diaginertia="0.00483538 0.00483538 0.00483538"/>
<joint name="fr3_joint6" axis="0 0 1" range="0.5445 4.5169" actuatorfrcrange="-12 12"/>
<joint name="fr3_joint6" axis="0 0 1" range="0.5445 4.5169" actuatorfrcrange="-12 12" actuatorgravcomp="true"/>
<geom mesh="fr3_link6_0" material="button_green" class="visual"/>
<geom mesh="fr3_link6_1" material="white" class="visual"/>
<geom mesh="fr3_link6_2" material="white" class="visual"/>
Expand All @@ -60,7 +106,7 @@
<body name="fr3_link7" pos="0.088 0 0" quat="1 1 0 0" gravcomp="1">
<inertial pos="0.00452258 0.00862619 -0.0161633" quat="0.120255 0.394761 -0.799132 0.437139"
mass="0.627143" diaginertia="3.076e-07 3.076e-07 3.076e-07"/>
<joint name="fr3_joint7" axis="0 0 1" range="-3.0159 3.0159" actuatorfrcrange="-12 12"/>
<joint name="fr3_joint7" axis="0 0 1" range="-3.0159 3.0159" actuatorfrcrange="-12 12" actuatorgravcomp="true"/>
<geom mesh="fr3_link7_0" material="black" class="visual"/>
<geom mesh="fr3_link7_1" material="white" class="visual"/>
<geom mesh="fr3_link7_2" material="white" class="visual"/>
Expand Down
Loading
Loading