More merge conflicts. Taking main changes then will integrate mine.
418 lines
23 KiB
XML
418 lines
23 KiB
XML
<mujoco model="stretch">
|
|
<compiler angle="radian" assetdir="assets" autolimits="true"/>
|
|
|
|
<option integrator="implicitfast" impratio="1" cone="elliptic" noslip_iterations="2">
|
|
<flag multiccd="enable"/>
|
|
</option>
|
|
|
|
<default>
|
|
<default class="stretch">
|
|
<geom mass="0" solref="0.005 1"/>
|
|
<general biastype="affine"/>
|
|
<default class="wheel">
|
|
<joint axis="0 0 -1" damping=".3"/>
|
|
<motor ctrlrange="-1 1" gear="3" forcerange="-100 100"/>
|
|
</default>
|
|
<default class="lift">
|
|
<joint type="slide" axis="0 0 1" damping="5" range="-0.5 .6"/>
|
|
<general ctrlrange="-0.5 .6" gainprm="300" biasprm="0 -300 -50" forcerange="-56 56"/>
|
|
</default>
|
|
<default class="telescope">
|
|
<joint type="slide" axis="0 0 1" damping="5" range="0 0.13"/>
|
|
<general ctrlrange="0 0.52" gainprm="100" biasprm="0 -100 -10" forcerange="-56 56"/>
|
|
</default>
|
|
<default class="head">
|
|
<joint axis="0 0 1" damping="1"/>
|
|
<position kp="10"/>
|
|
<default class="head_pan">
|
|
<joint range="-3.9 1.5"/>
|
|
<position ctrlrange="-3.9 1.5"/>
|
|
</default>
|
|
<default class="head_tilt">
|
|
<joint range="-1.53 0.79"/>
|
|
<position ctrlrange="-1.53 0.79"/>
|
|
</default>
|
|
</default>
|
|
<default class="wrist">
|
|
<joint axis="0 0 -1" range="-1.75 4" damping=".1"/>
|
|
<general gainprm="1" biasprm="0 -1 0" ctrlrange="-1.75 4" forcerange="-5 5"/>
|
|
</default>
|
|
<default class="finger_open">
|
|
<joint axis="0 0 1" range="-0.6 0.6" damping=".1"/>
|
|
</default>
|
|
<default class="finger_slide">
|
|
<joint type="slide" axis="1 0 0" range="-0.005 .04" damping=".1"/>
|
|
<general gainprm="2000" biasprm="0 -2000 -200" ctrlrange="-0.005 .04"/>
|
|
</default>
|
|
<default class="visual">
|
|
<geom group="2" type="mesh" contype="0" conaffinity="0"/>
|
|
</default>
|
|
<default class="collision">
|
|
<geom group="3" type="mesh"/>
|
|
<default class="caster">
|
|
<geom type="sphere" size=".02" pos="-0.24 0 .02" condim="1" priority="1"/>
|
|
</default>
|
|
<default class="rubber">
|
|
<geom condim="6" friction="0.8 0.02 0.01" priority="1"/>
|
|
</default>
|
|
</default>
|
|
</default>
|
|
</default>
|
|
|
|
<asset>
|
|
<texture type="2d" file="hand_crush.png"/>
|
|
<texture type="2d" file="serial.png"/>
|
|
<texture type="2d" file="mobile_base_right_corner_aruco_sticker.png"/>
|
|
<texture type="2d" file="mobile_base_left_corner_aruco_sticker.png"/>
|
|
<texture type="2d" file="hand_pinch.png"/>
|
|
<texture type="2d" file="arm_inner_wrist_aruco_sticker.png"/>
|
|
<texture type="2d" file="arm_top_wrist_aruco_sticker.png"/>
|
|
<texture type="2d" file="shoulder_aruco_sticker.png"/>
|
|
|
|
<material name="Caster_Rollers_Red" rgba="0.8 0.001381 0 1"/>
|
|
<material name="Generic_Black" rgba="0.036889 0.036889 0.036889 1"/>
|
|
<material name="3D_Print_Black" rgba="0.114435 0.114435 0.114435 1"/>
|
|
<material name="Pantone_Black_6_U" rgba="0.072272 0.076185 0.093059 1"/>
|
|
<material name="Plug_White" rgba="1 1 1 1"/>
|
|
<material name="Pure_Black" rgba="0 0 0 1"/>
|
|
<material name="Reflective_Metal" rgba="0.8 0.8 0.8 1"/>
|
|
<material name="Respeaker_Blue_Glow" rgba="0.006995 0.054480 0.799103 1"/>
|
|
<material name="Runstop_White_Glow" rgba="0.8 0.8 0.8 1"/>
|
|
<material name="Speaker_Housing_Black" rgba="0.003642 0.003642 0.003642 1"/>
|
|
<material name="Wheel_Rubber_Gray" rgba="0.418986 0.424087 0.429225 1"/>
|
|
<material name="Lightbar_Green" rgba="0.0 0.8 0.002964 1"/>
|
|
<material name="Pantone_705_U" rgba="1 0.723054 0.760525 1"/>
|
|
<material name="Pantone_Cool_Gray_4_U" rgba="0.473531 0.479320 0.485150 1"/>
|
|
<material name="Power_Button_Green" rgba="0.010852 0.023650 0.002724 1"/>
|
|
<material name="USB_Blue" rgba="0.000557 0.010166 0.8 1"/>
|
|
<material name="White_Plastic" rgba="1 1 1 1"/>
|
|
<material name="Laser_Black" rgba="0.03741 0.03741 0.03741 1"/>
|
|
<material name="Hand_Crush_Sticker" texture="hand_crush"/>
|
|
<material name="Stretch_Serial_Sticker" texture="serial"/>
|
|
<material name="Aruco_Right_Base_Sticker" texture="mobile_base_right_corner_aruco_sticker"/>
|
|
<material name="Aruco_Left_Base_Sticker" texture="mobile_base_left_corner_aruco_sticker"/>
|
|
<material name="Hand_Pinch_Sticker" texture="hand_pinch"/>
|
|
<material name="Carbon_Fiber" rgba="0.061246 0.061246 0.061246 1"/>
|
|
<material name="Aruco_Inner_Wrist_Sticker" texture="arm_inner_wrist_aruco_sticker"/>
|
|
<material name="Aruco_Top_Wrist_Sticker" texture="arm_top_wrist_aruco_sticker"/>
|
|
<material name="suction_rubber" rgba="0.25098 0.25098 0.25098 1"/>
|
|
<material name="Aruco_Shoulder_Sticker" texture="shoulder_aruco_sticker"/>
|
|
|
|
<mesh file="base_link_0.obj"/>
|
|
<mesh file="base_link_2.obj" inertia="shell"/>
|
|
<mesh file="base_link_3.obj"/>
|
|
<mesh file="base_link_4.obj"/>
|
|
<mesh file="base_link_5.obj"/>
|
|
<mesh file="base_link_6.obj" inertia="shell"/>
|
|
<mesh file="base_link_7.obj"/>
|
|
<mesh file="base_link_8.obj"/>
|
|
<mesh name="base_link_collision" file="base_link_casterless.stl"/>
|
|
<mesh file="link_aruco_right_base.obj" inertia="shell"/>
|
|
<mesh file="link_aruco_left_base.obj" inertia="shell"/>
|
|
<mesh file="respeaker_base.obj"/>
|
|
<mesh file="link_mast.obj"/>
|
|
<mesh file="link_head_0.obj"/>
|
|
<mesh file="link_head_1.obj"/>
|
|
<mesh file="link_head_2.obj"/>
|
|
<mesh file="link_head_3.obj"/>
|
|
<mesh file="link_head_4.obj"/>
|
|
<mesh file="link_head_5.obj"/>
|
|
<mesh file="link_head_6.obj"/>
|
|
<mesh file="link_head_7.obj"/>
|
|
<mesh file="link_head_8.obj"/>
|
|
<mesh file="link_head_9.obj"/>
|
|
<mesh file="link_head_10.obj"/>
|
|
<mesh file="link_head_11.obj"/>
|
|
<mesh file="link_head_pan_0.obj"/>
|
|
<mesh file="link_head_pan_1.obj"/>
|
|
<mesh file="link_head_tilt_0.obj"/>
|
|
<mesh file="link_head_tilt_1.obj"/>
|
|
<mesh file="link_right_wheel_0.obj"/>
|
|
<mesh file="link_right_wheel_1.obj"/>
|
|
<mesh file="link_left_wheel_0.obj"/>
|
|
<mesh file="link_left_wheel_1.obj"/>
|
|
<mesh file="link_lift_0.obj"/>
|
|
<mesh file="link_lift_1.obj" inertia="shell"/>
|
|
<mesh file="link_lift_2.obj"/>
|
|
<mesh file="link_lift_3.obj"/>
|
|
<mesh file="link_lift_4.obj"/>
|
|
<mesh file="link_lift_5.obj"/>
|
|
<mesh file="link_lift_6.obj"/>
|
|
<mesh file="link_lift_7.obj"/>
|
|
<mesh file="link_lift_8.obj"/>
|
|
<mesh file="link_lift_9.obj"/>
|
|
<mesh file="link_aruco_shoulder.obj" inertia="shell"/>
|
|
<mesh file="link_arm_l4_0.obj"/>
|
|
<mesh file="link_arm_l4_1.obj"/>
|
|
<mesh file="link_arm_l3_0.obj"/>
|
|
<mesh file="link_arm_l3_1.obj"/>
|
|
<mesh file="link_arm_l2_0.obj"/>
|
|
<mesh file="link_arm_l2_1.obj"/>
|
|
<mesh file="link_arm_l1_0.obj"/>
|
|
<mesh file="link_arm_l1_1.obj"/>
|
|
<mesh file="link_arm_l0_0.obj"/>
|
|
<mesh file="link_arm_l0_1.obj"/>
|
|
<mesh file="link_arm_l0_2.obj"/>
|
|
<mesh file="link_aruco_inner_wrist.obj" inertia="shell"/>
|
|
<mesh file="link_aruco_top_wrist.obj" inertia="shell"/>
|
|
<mesh file="laser.obj"/>
|
|
<mesh file="link_gripper_fingertip_left.stl"/>
|
|
<mesh file="link_gripper_fingertip_right.stl"/>
|
|
<mesh file="link_gripper_finger_left_0.obj" scale="0.9 1 1"/>
|
|
<mesh file="link_gripper_finger_left_1.obj" scale="0.9 1 1"/>
|
|
<mesh file="link_gripper_finger_right_0.obj" scale="0.9 1 1"/>
|
|
<mesh file="link_gripper_finger_right_1.obj" scale="0.9 1 1"/>
|
|
<mesh file="link_gripper_0.obj"/>
|
|
<mesh file="link_gripper_1.obj"/>
|
|
<mesh file="link_wrist_yaw.obj"/>
|
|
</asset>
|
|
|
|
<worldbody>
|
|
<body name="base_link" childclass="stretch">
|
|
<freejoint/>
|
|
<geom mesh="base_link_0" material="Caster_Rollers_Red" class="visual"/>
|
|
<geom mesh="base_link_2" material="Lightbar_Green" class="visual"/>
|
|
<geom mesh="base_link_3" material="Power_Button_Green" class="visual"/>
|
|
<geom mesh="base_link_4" material="USB_Blue" class="visual"/>
|
|
<geom mesh="base_link_5" material="Generic_Black" class="visual"/>
|
|
<geom mesh="base_link_6" material="Hand_Crush_Sticker" class="visual"/>
|
|
<geom mesh="base_link_7" material="Pantone_705_U" class="visual"/>
|
|
<geom mesh="base_link_8" material="Pantone_Cool_Gray_4_U" class="visual"/>
|
|
<geom class="collision" mesh="base_link_collision" mass="15.0"/>
|
|
<geom class="caster"/>
|
|
<body name="link_mast" pos="-0.067 0.135 0.0284" quat="1 1 0 0">
|
|
<geom material="Generic_Black" mesh="link_mast" class="visual"/>
|
|
<geom mesh="link_mast" class="collision" mass="1.8285"/>
|
|
</body>
|
|
<body name="link_head" pos="-0.067 0.134995 1.3584" quat="-1 0 0 1">
|
|
<geom mesh="link_head_0" material="Runstop_White_Glow" class="visual"/>
|
|
<geom mesh="link_head_1" material="Generic_Black" class="visual"/>
|
|
<geom mesh="link_head_2" material="Speaker_Housing_Black" class="visual"/>
|
|
<geom mesh="link_head_3" material="Reflective_Metal" class="visual"/>
|
|
<geom mesh="link_head_4" material="Reflective_Metal" class="visual"/>
|
|
<geom mesh="link_head_5" material="Pure_Black" class="visual"/>
|
|
<geom mesh="link_head_6" material="Reflective_Metal" class="visual"/>
|
|
<geom mesh="link_head_7" material="Plug_White" class="visual"/>
|
|
<geom mesh="link_head_8" material="3D_Print_Black" class="visual"/>
|
|
<geom mesh="link_head_9" material="Respeaker_Blue_Glow" class="visual"/>
|
|
<geom mesh="link_head_10" material="Pantone_Black_6_U" class="visual"/>
|
|
<geom mesh="link_head_11" material="Generic_Black" class="visual"/>
|
|
<geom mesh="link_head_10" class="collision" mass="0.833027236718691"/>
|
|
</body>
|
|
<body name="link_aruco_right_base" pos="-0.0015028 -0.130497 0.159748" quat="1 0 0 -1">
|
|
<geom material="Aruco_Right_Base_Sticker" mesh="link_aruco_right_base" class="visual" mass="3.6E-06"/>
|
|
<geom mesh="link_aruco_right_base" class="collision"/>
|
|
</body>
|
|
<body name="link_aruco_left_base" pos="-0.0015028 0.130497 0.159748" quat="1 0 0 -1">
|
|
<geom material="Aruco_Left_Base_Sticker" mesh="link_aruco_left_base" class="visual" mass="3.6E-06"/>
|
|
<geom mesh="link_aruco_left_base" class="collision"/>
|
|
</body>
|
|
<body name="laser" pos="0.004 0 0.1664" quat="0 0 0 1">
|
|
<geom material="Laser_Black" mesh="laser" class="visual" mass="0.24"/>
|
|
<geom mesh="laser" class="collision"/>
|
|
</body>
|
|
<body name="link_right_wheel" pos="0 -0.17035 0.0508" quat="1 -1 0 0">
|
|
<joint name="joint_right_wheel" class="wheel"/>
|
|
<geom mesh="link_right_wheel_0" material="Wheel_Rubber_Gray" class="visual" mass="0.15"/>
|
|
<geom mesh="link_right_wheel_1" material="Generic_Black" class="visual"/>
|
|
<geom class="collision" type="cylinder" size=".05 .0125" pos="0 0 0.0125"/>
|
|
</body>
|
|
<body name="link_left_wheel" pos="0 0.17035 0.0508" quat="1 -1 0 0">
|
|
<joint name="joint_left_wheel" class="wheel"/>
|
|
<geom mesh="link_left_wheel_0" material="Wheel_Rubber_Gray" class="visual" mass="0.15"/>
|
|
<geom mesh="link_left_wheel_1" material="Generic_Black" class="visual"/>
|
|
<geom class="collision" type="cylinder" size=".05 .0125" pos="0 0 -0.0125"/>
|
|
</body>
|
|
<body name="link_lift" gravcomp="1" pos="-0.104385 0.134999 0.695" quat="1 0 0 1">
|
|
<joint name="joint_lift" class="lift"/>
|
|
<geom mesh="link_lift_0" material="Pantone_705_U" class="visual"/>
|
|
<geom mesh="link_lift_2" material="Pure_Black" class="visual"/>
|
|
<geom mesh="link_lift_3" material="Reflective_Metal" class="visual"/>
|
|
<geom mesh="link_lift_4" material="Plug_White" class="visual"/>
|
|
<geom mesh="link_lift_5" material="Pantone_Black_6_U" class="visual"/>
|
|
<geom mesh="link_lift_6" material="Generic_Black" class="visual"/>
|
|
<geom mesh="link_lift_7" material="Generic_Black" class="visual"/>
|
|
<geom mesh="link_lift_8" material="3D_Print_Black" class="visual"/>
|
|
<geom mesh="link_lift_9" material="Pantone_Black_6_U" class="visual"/>
|
|
<geom mesh="link_lift_0" class="collision"/>
|
|
<geom mesh="link_lift_2" class="collision"/>
|
|
<geom mesh="link_lift_3" class="collision"/>
|
|
<geom mesh="link_lift_4" class="collision"/>
|
|
<geom mesh="link_lift_5" class="collision"/>
|
|
<geom mesh="link_lift_6" class="collision"/>
|
|
<geom mesh="link_lift_7" class="collision"/>
|
|
<geom mesh="link_lift_8" class="collision" mass="1.5"/>
|
|
<geom mesh="link_lift_9" class="collision" mass="1.5"/>
|
|
<body name="link_arm_l4" gravcomp="1">
|
|
<geom mesh="link_arm_l4_0" pos="-0.2547 0 0" quat="0.5 0.5 -0.5 -0.5" material="Carbon_Fiber" class="visual"/>
|
|
<geom mesh="link_arm_l4_1" pos="-0.2547 0 0" quat="0.5 0.5 -0.5 -0.5" material="3D_Print_Black" class="visual"/>
|
|
<geom mesh="link_arm_l4_0" pos="-0.2547 0 0" quat="0.5 0.5 -0.5 -0.5" class="collision" mass="0.168095"/>
|
|
<geom mesh="link_arm_l4_1" pos="-0.2547 0 0" quat="0.5 0.5 -0.5 -0.5" class="collision"/>
|
|
<body name="link_arm_l3" pos="-0.2677 0 0" quat="0.5 0.5 -0.5 -0.5" gravcomp="1">
|
|
<joint name="joint_arm_l3" class="telescope"/>
|
|
<geom mesh="link_arm_l3_0" material="Carbon_Fiber" class="visual" mass="0.162893"/>
|
|
<geom mesh="link_arm_l3_1" material="3D_Print_Black" class="visual"/>
|
|
<geom mesh="link_arm_l3_0" class="collision"/>
|
|
<geom mesh="link_arm_l3_1" class="collision"/>
|
|
<body name="link_arm_l2" pos="0 0 0.013" gravcomp="1">
|
|
<joint name="joint_arm_l2" class="telescope"/>
|
|
<geom mesh="link_arm_l2_0" material="Carbon_Fiber" class="visual" mass="0.157139"/>
|
|
<geom mesh="link_arm_l2_1" material="3D_Print_Black" class="visual"/>
|
|
<geom mesh="link_arm_l2_0" class="collision"/>
|
|
<geom mesh="link_arm_l2_1" class="collision"/>
|
|
<body name="link_arm_l1" pos="0 0 0.013" gravcomp="1">
|
|
<joint name="joint_arm_l1" class="telescope"/>
|
|
<geom mesh="link_arm_l1_0" material="Carbon_Fiber" class="visual" mass="0.151382"/>
|
|
<geom mesh="link_arm_l1_1" material="3D_Print_Black" class="visual"/>
|
|
<geom mesh="link_arm_l1_0" class="collision"/>
|
|
<geom mesh="link_arm_l1_1" class="collision"/>
|
|
<body name="link_arm_l0" pos="0 0 -0.01375" quat="1 0 0 0" gravcomp="1">
|
|
<joint name="joint_arm_l0" class="telescope"/>
|
|
<geom mesh="link_arm_l0_0" material="3D_Print_Black" class="visual"/>
|
|
<geom mesh="link_arm_l0_1" material="Carbon_Fiber" class="visual" mass="0.28501"/>
|
|
<geom mesh="link_arm_l0_2" material="Generic_Black" class="visual"/>
|
|
<geom mesh="link_arm_l0_0" class="collision"/>
|
|
<geom mesh="link_arm_l0_1" class="collision"/>
|
|
<geom mesh="link_arm_l0_2" class="collision"/>
|
|
<body name="link_aruco_top_wrist" pos="0.04725 0.029285 0" quat="0 0 1 1">
|
|
<geom material="Aruco_Top_Wrist_Sticker" mesh="link_aruco_top_wrist" class="visual" mass="3.6E-06"/>
|
|
<geom mesh="link_aruco_top_wrist" class="collision"/>
|
|
</body>
|
|
<body name="link_aruco_inner_wrist" pos="0.04725 -0.0119 -0.02725" quat="0 0 1 0">
|
|
<geom material="Aruco_Inner_Wrist_Sticker" mesh="link_aruco_inner_wrist" class="visual"
|
|
mass="3.6E-06"/>
|
|
<geom mesh="link_aruco_inner_wrist" class="collision"/>
|
|
</body>
|
|
<body name="link_wrist_yaw" pos="0.083 -0.03075 0" quat="1 1 0 0" gravcomp="1">
|
|
<joint name="joint_wrist_yaw" class="wrist"/>
|
|
<geom material="Generic_Black" mesh="link_wrist_yaw" class="visual"/>
|
|
<geom mesh="link_wrist_yaw" class="collision"/>
|
|
<geom quat="0 1 -1 0" mesh="link_gripper_0" material="Generic_Black" class="visual"/>
|
|
<geom quat="0 1 -1 0" mesh="link_gripper_1" material="3D_Print_Black" class="visual" mass="0.142377"/>
|
|
<geom quat="0 1 -1 0" mesh="link_gripper_0" class="collision"/>
|
|
<geom quat="0 1 -1 0" mesh="link_gripper_1" class="collision"/>
|
|
<body name="link_gripper_slider" quat="0.183013 -0.683017 -0.683009 -0.183013"
|
|
pos="0 0.047231 0.04679" gravcomp="1">
|
|
<joint name="joint_gripper_slide" class="finger_slide"/>
|
|
<geom type="box" size=".03 .005 .005" mass=".05" class="visual" rgba="0 0 0 0"/>
|
|
<body name="link_gripper_finger_left" pos="0 0.0101513 0" gravcomp="1">
|
|
<joint name="joint_gripper_finger_left_open" class="finger_open"/>
|
|
<geom mesh="link_gripper_finger_left_0" material="Reflective_Metal" class="visual"
|
|
mass="0.0378216"/>
|
|
<geom mesh="link_gripper_finger_left_1" material="White_Plastic" class="visual"/>
|
|
<geom class="collision" size="0.00426947 0.00524467 0.08" pos="0.1 0.005 0"
|
|
quat="0.474728 0.474728 0.524055 0.524055" type="box"/>
|
|
<geom mesh="link_gripper_finger_left_1" class="collision"/>
|
|
<body name="rubber_tip_left" pos="0.171099 0.014912 0" quat="1 1 0 0">
|
|
<joint name="rubber_left_x" type="hinge" axis="1 0 0" damping="0.001" stiffness="0.05"/>
|
|
<joint name="rubber_left_y" type="hinge" axis="0 1 0" damping="0.001" stiffness="0.05"/>
|
|
<geom class="visual" mesh="link_gripper_fingertip_left" mass="0.005" material="suction_rubber"/>
|
|
<geom class="rubber" type="cylinder" size=".02 .005" pos="0 0 .012"/>
|
|
</body>
|
|
</body>
|
|
<body name="link_gripper_finger_right" pos="0 -0.0100487 0" quat="0 0 -1 0" gravcomp="1">
|
|
<joint name="joint_gripper_finger_right_open" class="finger_open"/>
|
|
<geom mesh="link_gripper_finger_right_0" material="Reflective_Metal" class="visual"
|
|
mass="0.0378216"/>
|
|
<geom mesh="link_gripper_finger_right_1" material="White_Plastic" class="visual"/>
|
|
<geom class="collision" size="0.00426947 0.00524467 0.08" pos="-0.1 -0.005 0"
|
|
quat="0.474728 0.474728 0.524055 0.524055" type="box"/>
|
|
<geom mesh="link_gripper_finger_right_1" class="collision"/>
|
|
<body name="rubber_tip_right" pos="-0.171099 -0.014912 0" quat="1 -1 0 0">
|
|
<joint name="rubber_right_x" type="hinge" axis="1 0 0" damping="0.001" stiffness="0.05"/>
|
|
<joint name="rubber_right_y" type="hinge" axis="0 1 0" damping="0.001" stiffness="0.05"/>
|
|
<geom class="visual" material="suction_rubber" mesh="link_gripper_fingertip_right"
|
|
mass="0.005"/>
|
|
<geom class="rubber" type="cylinder" size=".02 .005" pos="0 0 .012"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="link_aruco_shoulder" pos="-0.0133769 0.0558541 0.0865" quat="1 0 0 0">
|
|
<geom material="Aruco_Shoulder_Sticker" mesh="link_aruco_shoulder" class="visual" mass="3.6E-06"/>
|
|
<geom mesh="link_aruco_shoulder" class="collision"/>
|
|
</body>
|
|
</body>
|
|
<body name="link_head_pan" pos="0.00610002 0 1.3552" quat="-1 0 0 0">
|
|
<joint name="joint_head_pan" class="head_pan"/>
|
|
<geom mesh="link_head_pan_0" material="3D_Print_Black" class="visual"/>
|
|
<geom mesh="link_head_pan_1" material="Generic_Black" class="visual" mass="0.127376"/>
|
|
<geom mesh="link_head_pan_0" class="collision"/>
|
|
<geom mesh="link_head_pan_1" class="collision"/>
|
|
<body name="link_head_tilt" pos="-0.0013 0.0277625 -0.0533108" quat="1 1 0 0">
|
|
<joint name="joint_head_tilt" class="head_tilt"/>
|
|
<geom mesh="link_head_tilt_0" material="Pantone_Cool_Gray_4_U" class="visual" mass="0.1311085"/>
|
|
<geom mesh="link_head_tilt_1" material="3D_Print_Black" class="visual" mass="0.1311085"/>
|
|
<geom mesh="link_head_tilt_0" class="collision"/>
|
|
<geom mesh="link_head_tilt_1" class="collision"/>
|
|
<body name="realsense" pos="0.0406 0.0053 0.0307">
|
|
<camera name="camera_rgb" pos="0 0.015 0" quat=".5 -.5 -.5 .5"/>
|
|
<camera name="camera_depth" quat=".5 -.5 -.5 .5"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</worldbody>
|
|
|
|
<contact>
|
|
<exclude body1="link_head_pan" body2="link_head"/>
|
|
<exclude body1="link_left_wheel" body2="base_link"/>
|
|
<exclude body1="link_right_wheel" body2="base_link"/>
|
|
<exclude body1="link_lift" body2="link_mast"/>
|
|
<exclude body1="link_lift" body2="link_head"/>
|
|
<exclude body1="link_arm_l0" body2="link_arm_l4"/>
|
|
<exclude body1="link_arm_l1" body2="link_arm_l4"/>
|
|
<exclude body1="link_arm_l2" body2="link_arm_l4"/>
|
|
<exclude body1="link_arm_l3" body2="link_arm_l4"/>
|
|
<exclude body1="link_arm_l0" body2="link_arm_l2"/>
|
|
<exclude body1="link_arm_l0" body2="link_arm_l3"/>
|
|
<exclude body1="link_arm_l0" body2="link_lift"/>
|
|
<exclude body1="link_arm_l1" body2="link_arm_l3"/>
|
|
<exclude body1="link_arm_l1" body2="link_lift"/>
|
|
<exclude body1="link_arm_l2" body2="link_lift"/>
|
|
<exclude body1="link_gripper_finger_left" body2="link_wrist_yaw"/>
|
|
<exclude body1="link_gripper_finger_right" body2="link_wrist_yaw"/>
|
|
</contact>
|
|
|
|
<tendon>
|
|
<fixed name="forward">
|
|
<joint joint="joint_left_wheel" coef=".5"/>
|
|
<joint joint="joint_right_wheel" coef=".5"/>
|
|
</fixed>
|
|
<fixed name="turn">
|
|
<joint joint="joint_left_wheel" coef="-.5"/>
|
|
<joint joint="joint_right_wheel" coef=".5"/>
|
|
</fixed>
|
|
<fixed name="extend">
|
|
<joint joint="joint_arm_l0" coef="1"/>
|
|
<joint joint="joint_arm_l1" coef="1"/>
|
|
<joint joint="joint_arm_l2" coef="1"/>
|
|
<joint joint="joint_arm_l3" coef="1"/>
|
|
</fixed>
|
|
</tendon>
|
|
|
|
<equality>
|
|
<joint joint1="joint_arm_l0" joint2="joint_arm_l1"/>
|
|
<joint joint1="joint_arm_l1" joint2="joint_arm_l2"/>
|
|
<joint joint1="joint_arm_l2" joint2="joint_arm_l3"/>
|
|
<joint joint1="joint_gripper_finger_left_open" joint2="joint_gripper_slide" polycoef="0 10 0 0 0" solref="0.005 1"/>
|
|
<joint joint1="joint_gripper_finger_right_open" joint2="joint_gripper_slide" polycoef="0 10 0 0 0" solref="0.005 1"/>
|
|
</equality>
|
|
|
|
<actuator>
|
|
<motor name="forward" tendon="forward" class="wheel"/>
|
|
<motor name="turn" tendon="turn" class="wheel"/>
|
|
<general name="lift" joint="joint_lift" class="lift"/>
|
|
<general name="arm_extend" tendon="extend" class="telescope"/>
|
|
<general name="wrist_yaw" joint="joint_wrist_yaw" class="wrist"/>
|
|
<general name="grip" joint="joint_gripper_slide" class="finger_slide"/>
|
|
<position name="head_pan" joint="joint_head_pan" class="head_pan"/>
|
|
<position name="head_tilt" joint="joint_head_tilt" class="head_tilt"/>
|
|
</actuator>
|
|
</mujoco>
|