Skip to content
Permalink
main
Switch branches/tags

Name already in use

A tag already exists with the provided branch name. Many Git commands accept both tag and branch names, so creating this branch may cause unexpected behavior. Are you sure you want to create this branch?
Go to file
 
 
Cannot retrieve contributors at this time
<mujoco model="jaco2">
<compiler angle="radian" meshdir="meshes" balanceinertia="true"/>
<default>
<light castshadow="false" diffuse="1 1 1" />
<camera fovy="60" />
</default>
<custom>
<numeric name="START_ANGLES" data="2.0 3.14 1.57 4.71 0.0 3.04" />
<numeric name="N_GRIPPER_JOINTS" data="3" />
<text name="google_id" data="1doam-DgkW7OSPnwWZQM84edzX84ot-GK" />
</custom>
<asset>
<!-- arm models -->
<mesh file="link0.STL" />
<mesh file="link1.STL"/>
<mesh file="link2.STL"/>
<mesh file="link3.STL"/>
<mesh file="link4_5.STL"/>
<mesh file="hand_3finger.STL"/>
<mesh file="finger_distal.STL"/>
<mesh file="finger_proximal.STL"/>
<mesh file="ring_big.STL"/>
<mesh file="ring_small.STL"/>
<texture name="floor_tile" file="meshes/floor_tile.png" width="3000" height="3000" type="2d"/>
<material name="tile" texture="floor_tile" specular="0" shininess="0" reflectance="0" emission="1" />
<material name="carbon" specular="1" shininess="1" reflectance="1" rgba="0.05 0.05 0.05 1" emission="1" />
<material name="grey_plastic" specular="0.5" shininess="0" reflectance="0" rgba="0.12 0.14 0.14 1" emission="1" />
<texture name="abr_logo" file="meshes/abr_logo.png" width="193" height="193" type="2d"/>
<material name="logo" texture="abr_logo"/>
<texture name="abr_logo_flip" file="meshes/abr_logo.png" width="193" height="193" type="2d" hflip="true"/>
<material name="logo_flip" texture="abr_logo_flip"/>
<texture name="foam_blocks" file="meshes/foam_blocks.png" width="2744" height="2744" type="2d"/>
<material name="foam" texture="foam_blocks" specular="0" shininess="0" reflectance="0" emission="1" />
</asset>
<worldbody>
<geom name="floor_foam_block" pos="0 0 0" size="0.5 0.5 0.05" type="plane" rgba="1 0.83 0.61 1" material="foam"/>
<geom name="floor_grey_tile" pos="0 0 -0.001" size="0.75 0.75 0.05" type="plane" material="tile"/>
<!-- control visualizations -->
<body name="hand" pos="0 0 -0.15" mocap="true">
<geom type="box" size=".002 .004 .006" rgba="0 .9 0 .5" contype="2" conaffinity="2"/>
</body>
<body name="target" pos="0 0 -0.15" mocap="true">
<geom name="target" type="sphere" size="0.05" rgba=".9 0 0 .5" contype="4" conaffinity="4"/>
</body>
<body name="target_orientation" pos="0 0 -0.15" mocap="true">
<geom type="box" size=".02 .04 .06" rgba=".9 0 0 .5" contype="8" conaffinity="8"/>
</body>
<body name="path_planner" pos="0 0 -0.15" mocap="true">
<geom type="sphere" size="0.05" rgba="0 1 1 0.5" contype="16" conaffinity="16"/>
</body>
<body name="path_planner_orientation" pos="0 0 -0.15" mocap="true">
<geom type="box" size=".02 .04 .06" rgba="0 1 1 .5" contype="32" conaffinity="32"/>
</body>
<body name="obstacle" pos="0 0 -0.15" mocap="true">
<geom type="sphere" size="0.05" rgba="0 0 1 1"/>
</body>
<light directional="true" pos="-0.5 0.5 3" dir="0 0 -1" />
<body name="base_link" pos="0 0 0">
<geom name="link0" type="mesh" mesh="link0" pos="0 0 0" material="carbon"/>
<inertial pos="0.000000 0.000000 0.125500" mass="1.226" diaginertia="0.25 0.25 0.25"/>
<geom type="sphere" size="0.025" pos="0.000000 0.000000 0.125500" rgba="1 0.5 0 1"/>
<body name="link1" pos="0 0 0.157">
<inertial pos="-0.000042 -0.001285 0.112784" mass="0.754000" diaginertia="0.3 0.3 0.3"/>
<geom name="link1" type="mesh" mesh="link1" pos="0 0 0" euler="0 3.14 0" material="carbon"/>
<!-- <geom name="ring0" type="mesh" mesh="ring_big" material="grey_plastic"/> -->
<geom name="joint_logo0" type="cylinder" size="0.032 0.005" material="logo" pos="0 -0.0364 0.1186" euler="1.6 0 0"/>
<joint name="joint0" axis="0 0 -1" pos="0 0 0"/>
<body name="link2" pos="0 0.0016 0.1186">
<inertial pos="0.000014 0.009353 0.329006" mass="1.010000" diaginertia="0.3 0.3 0.3"/>
<geom name="link2" type="mesh" mesh="link2" pos="0 0 0" euler="1.57 0 3.14" material="carbon"/>
<geom name="ring1" type="mesh" mesh="ring_big" material="grey_plastic" euler="1.57 0 0"/>
<geom name="joint_logo1" type="cylinder" size="0.032 0.005" material="logo_flip" pos="0 0.038 0" euler="1.52 0 0"/>
<geom name="joint_logo2" type="cylinder" size="0.032 0.005" material="logo_flip" pos="0 0.0385 0.410" euler="1.62 0 0"/>
<joint name="joint1" pos="0 0 0" axis="0 -1 0" ref="3.14" limited="true" range="0.872665 5.41052"/>
<body name="link3" pos="0 0 0.410">
<inertial pos="-0.000039 -0.018069 0.153270" mass="0.559000" diaginertia="0.275 0.275 0.275"/>
<geom name="link3" type="mesh" mesh="link3" pos="0 0 0" euler="1.57 3.14 0" material="carbon"/>
<geom name="ring2" type="mesh" mesh="ring_big" material="grey_plastic" euler="1.57 0 0"/>
<joint name="joint2" pos="0 0 0" axis="0 1 0" ref="3.14" limited="true" range="0.331613 5.95157"/>
<geom name="joint_logo3" type="cylinder" size="0.032 0.005" material="logo" pos="0 -0.038 0" euler="1.54 0 0"/>
<body name="link4" pos="0 -0.0115 0.2072">
<inertial pos="0.000000 0.032302 0.059705" mass="0.417000" diaginertia="0.175 0.175 0.175"/>
<geom name="link4" type="mesh" mesh="link4_5" euler="3.14 0 0" material="carbon"/>
<geom name="ring3" type="mesh" mesh="ring_small" material="grey_plastic"/>
<joint name="joint3" pos="0 0 0" axis="0 0 -1" ref="0"/>
<body name="link5" pos="0 0.037 0.0641">
<inertial pos="-0.000000 0.035545 0.057833" mass="0.417" diaginertia="0.175 0.175 0.175"/>
<geom name="link5" type="mesh" mesh="link4_5" euler="-1.0472 3.14 0" material="carbon"/>
<geom name="ring4" type="mesh" mesh="ring_small" material="grey_plastic" euler="-1.0471 0 0"/>
<joint name="joint4" pos="0 0 0" axis="0 -1.9 -1.1" ref="0"/>
<body name="link6" pos="0 0.037 0.0641">
<inertial pos="0.000030 -0.006840 0.082220" mass="0.727000" diaginertia="0.025 0.025 0.025"/>
<geom name="link6" type="mesh" mesh="hand_3finger" euler="3.14 0 0" material="carbon" solimp="0.97 0.97 0.01" solref="0.01 1" condim="6" />
<geom name="ring5" type="mesh" mesh="ring_small" material="grey_plastic"/>
<joint name="joint5" pos="0 0 0" axis="0 0 -1" ref="0"/>
<!-- for fingertip EE -->
<!-- <body name="EE" pos="0 0 0.20222" euler="0 0 0"> -->
<!-- </body> -->
<!-- for palm EE -->
<body name="EE" pos="0 0 0.12" euler="0 0 0">
</body>
<body name="thumb_proximal" pos="0.002786 -0.03126 0.114668" quat="0.95922726 0.262085 0.02762996 -0.10213274">
<geom name="thumb_proximal" type="mesh" mesh="finger_proximal" euler="0 -1.5707 0" friction="1 0.5 0.01" solimp="0.95 0.95 0.01 0.5 6" solref="0.01 1" condim="6" margin="0.0"/>
<joint name="joint_thumb" pos="0 0 0" axis="1 0 0" ref="1.1" limited="true" range="-0.2 1.1" solimplimit="0.95 0.95 0.01" solreflimit="0.01 1" stiffness="5" springref="0.0" damping="0.35"/>
<body name="thumb_distal" pos="0 -0.003 0.044">
<geom name="thumb_distal" type="mesh" mesh="finger_distal" euler="0 -1.5707 0" friction="1 0.5 0.01" solimp="0.95 0.95 0.01 0.5 6" solref="0.01 1" condim="6" margin="0.0"/>
<joint name="joint_thumb_distal" pos="0 0 0" axis="-1 0 0" ref="0" limited="true" range="-0.4 0.4" stiffness="5" springref="-0.4" damping="0.5" solimplimit="0.95 0.95 0.01" solreflimit="0.01 1"/>
</body>
</body>
<body name="index_proximal" pos="0.022256 0.027073 0.114668" quat="0.96181018 -0.25771638 0.0238668 -0.08907205">
<geom name="index_proximal" type="mesh" mesh="finger_proximal" quat="5.63312174e-04 7.06824957e-01 -5.62863772e-04 7.07388045e-01" friction="1 0.5 0.01" solimp="0.95 0.95 0.01 0.5 6" solref="0.01 1" condim="6" margin="0.0"/>
<joint name="joint_index" pos="0 0 0" axis="-1 0 0" ref="1.1" limited="true" range="-0.2 1.1" solimplimit="0.95 0.95 0.01" solreflimit="0.01 1" stiffness="5" springref="0.0" damping="0.35"/>
<body name="index_distal" pos="0 0.003 0.044">
<geom name="index_distal" type="mesh" mesh="finger_distal" quat="5.63312174e-04 7.06824957e-01 -5.62863772e-04 7.07388045e-01" friction="1 0.5 0.01" solimp="0.95 0.95 0.01 0.5 6" solref="0.01 1" condim="6" margin="0.0"/>
<joint name="joint_index_distal" pos="0 0 0" axis="1 0 0" ref="0" limited="true" range="-0.4 0.4" stiffness="5" springref="-0.4" damping="0.5" solimplimit="0.95 0.95 0.01" solreflimit="0.01 1"/>
</body>
</body>
<body name="pinky_proximal" pos="-0.022256 0.027073 0.114816" quat="0.96181018 -0.25771638 -0.0238668 0.08907205">
<geom name="pinky_proximal" type="mesh" mesh="finger_proximal" quat="5.63312174e-04 7.06824957e-01 -5.62863772e-04 7.07388045e-01" friction="1 0.5 0.01" solimp="0.95 0.95 0.01 0.5 6" solref="0.01 1" condim="6" margin="0.0"/>
<joint name="joint_pinky" pos="0 0 0" axis="-1 0 0" ref="1.1" limited="true" range="-0.2 1.1" solimplimit="0.95 0.95 0.01" solreflimit="0.01 1" stiffness="5" springref="0.0" damping="0.35"/>
<body name="pinky_distal" pos="0 0.003 0.044">
<geom name="pinky_distal" type="mesh" mesh="finger_distal" quat="5.63312174e-04 7.06824957e-01 -5.62863772e-04 7.07388045e-01" friction="1 0.5 0.01" solimp="0.95 0.95 0.01 0.5 6" solref="0.01 1" condim="6" margin="0.0"/>
<joint name="joint_pinky_distal" pos="0 0 0" axis="1 0 0" ref="0" limited="true" range="-0.4 0.4" stiffness="5" springref="0.4" damping="0.5" solimplimit="0.95 0.95 0.01" solreflimit="0.01 1"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<motor name="joint0_motor" joint="joint0"/>
<motor name="joint1_motor" joint="joint1"/>
<motor name="joint2_motor" joint="joint2"/>
<motor name="joint3_motor" joint="joint3"/>
<motor name="joint4_motor" joint="joint4"/>
<motor name="joint5_motor" joint="joint5"/>
<motor name="joint_thumb_motor" joint="joint_thumb"/>
<motor name="joint_index_motor" joint="joint_index"/>
<motor name="joint_pinky_motor" joint="joint_pinky"/>
</actuator>
</mujoco>