pusher.xml 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990
  1. <mujoco model="pusher">
  2. <compiler inertiafromgeom="true" angle="radian" coordinate="local"/>
  3. <default>
  4. <joint armature='0.04' damping="0" limited="true"/>
  5. <geom friction=".8 .1 .1" density="300" margin="0.002" condim="1" contype="0" conaffinity="0"/>
  6. </default>
  7. <option timestep="0.01" gravity="0 0 0" integrator="RK4" />
  8. <worldbody>
  9. <!--Arena-->
  10. <geom name="table" type="plane" pos="0 0.5 -0.325" size="1 1 0.1" contype="1" conaffinity="1"/>
  11. <!--Arm-->
  12. <body name="shoulder_pan_link" pos="0 -0.6 0">
  13. <geom name="e1" type="sphere" rgba="0.6 0.6 0.6 1" pos="-0.06 0.05 0.2" size="0.05" />
  14. <geom name="e2" type="sphere" rgba="0.6 0.6 0.6 1" pos=" 0.06 0.05 0.2" size="0.05" />
  15. <geom name="e1p" type="sphere" rgba="0.1 0.1 0.1 1" pos="-0.06 0.09 0.2" size="0.03" />
  16. <geom name="e2p" type="sphere" rgba="0.1 0.1 0.1 1" pos=" 0.06 0.09 0.2" size="0.03" />
  17. <geom name="sp" type="capsule" fromto="0 0 -0.4 0 0 0.2" size="0.1" />
  18. <joint name="shoulder_pan_joint" type="hinge" pos="0 0 0" axis="0 0 1" range="-2.2854 1.714602" damping="0" />
  19. <body name="shoulder_lift_link" pos="0.1 0 0">
  20. <geom name="sl" type="capsule" fromto="0 -0.1 0 0 0.1 0" size="0.1" />
  21. <joint name="shoulder_lift_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-0.5236 1.3963" damping="0" />
  22. <body name="upper_arm_roll_link" pos="0 0 0">
  23. <geom name="uar" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" />
  24. <joint name="upper_arm_roll_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.5 1.7" damping="0" />
  25. <body name="upper_arm_link" pos="0 0 0">
  26. <geom name="ua" type="capsule" fromto="0 0 0 0.4 0 0" size="0.06" />
  27. <body name="elbow_flex_link" pos="0.4 0 0">
  28. <geom name="ef" type="capsule" fromto="0 -0.02 0 0.0 0.02 0" size="0.06" />
  29. <joint name="elbow_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-2.3213 0" damping="0" />
  30. <body name="forearm_roll_link" pos="0 0 0">
  31. <geom name="fr" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" />
  32. <joint name="forearm_roll_joint" type="hinge" limited="true" pos="0 0 0" axis="1 0 0" damping="0" range="-1.5 1.5"/>
  33. <body name="forearm_link" pos="0 0 0">
  34. <geom name="fa" type="capsule" fromto="0 0 0 0.291 0 0" size="0.05" />
  35. <body name="wrist_flex_link" pos="0.321 0 0">
  36. <geom name="wf" type="capsule" fromto="0 -0.02 0 0 0.02 0" size="0.01" />
  37. <joint name="wrist_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-1.094 0" damping="0" />
  38. <body name="wrist_roll_link" pos="0 0 0">
  39. <joint name="wrist_roll_joint" type="hinge" pos="0 0 0" limited="true" axis="1 0 0" damping="0" range="-1.5 1.5"/>
  40. <body name="fingertip" pos="0 0 0">
  41. <geom name="tip_arml" type="sphere" pos="0.1 -0.1 0." size="0.01" />
  42. <geom name="tip_armr" type="sphere" pos="0.1 0.1 0." size="0.01" />
  43. </body>
  44. <geom type="capsule" fromto="0 -0.1 0. 0.0 +0.1 0" size="0.02" contype="1" conaffinity="1" />
  45. <geom type="capsule" fromto="0 -0.1 0. 0.1 -0.1 0" size="0.02" contype="1" conaffinity="1" />
  46. <geom type="capsule" fromto="0 +0.1 0. 0.1 +0.1 0." size="0.02" contype="1" conaffinity="1" />
  47. </body>
  48. </body>
  49. </body>
  50. </body>
  51. </body>
  52. </body>
  53. </body>
  54. </body>
  55. </body>
  56. <!--Object-->
  57. <body name="object" pos="0.45 -0.05 -0.275" >
  58. <geom rgba="1 1 1 0" type="sphere" size="0.05 0.05 0.05" density="0.00001" conaffinity="0"/>
  59. <geom rgba="1 1 1 1" type="cylinder" size="0.05 0.05 0.05" density="0.00001" contype="1" conaffinity="0"/>
  60. <joint name="object_x" type="slide" pos="0 0 0" axis="1 0 0" range="-10.3213 10.3" damping="0"/>
  61. <joint name="object_y" type="slide" pos="0 0 0" axis="0 1 0" range="-10.3213 10.3" damping="0"/>
  62. </body>
  63. <!--Target-->
  64. <body name="target" pos="0.45 -0.05 -0.3230">
  65. <geom rgba="1 0 0 1" type="cylinder" size="0.08 0.001 0.1" density='0.00001' contype="0" conaffinity="0"/>
  66. <joint name="target_x" type="slide" pos="0 0 0" axis="1 0 0" range="-10.3213 10.3" damping="0"/>
  67. <joint name="target_y" type="slide" pos="0 0 0" axis="0 1 0" range="-10.3213 10.3" damping="0"/>
  68. </body>
  69. </worldbody>
  70. <actuator>
  71. <motor joint="shoulder_pan_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
  72. <motor joint="shoulder_lift_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
  73. <motor joint="upper_arm_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
  74. <motor joint="elbow_flex_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
  75. <motor joint="forearm_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
  76. <motor joint="wrist_flex_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
  77. <motor joint="wrist_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true"/>
  78. </actuator>
  79. </mujoco>