update G1 urdf&mjcf
This commit is contained in:
parent
8bca7f8907
commit
dd4fa6866e
|
@ -1,13 +0,0 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(g1_description)
|
||||
|
||||
find_package(catkin REQUIRED)
|
||||
|
||||
catkin_package()
|
||||
|
||||
find_package(roslaunch)
|
||||
|
||||
foreach(dir launch meshes)
|
||||
install(DIRECTORY ${dir}/
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
|
||||
endforeach(dir)
|
|
@ -5,54 +5,18 @@
|
|||
This package includes a streamlined robot description (URDF & MJCF) for the [Unitree G1](https://www.unitree.com/g1/), developed by [Unitree Robotics](https://www.unitree.com/).
|
||||
|
||||
<p align="center">
|
||||
<img src="g1.png" width="500"/>
|
||||
<img src="images/g1_23dof.png" width="45%"/>
|
||||
<img src="images/g1_29dof.png" width="45%"/>
|
||||
<img src="images/g1_29dof_with_hand.png" width="45%"/>
|
||||
<img src="images/g1_dual_arm.png" width="45%"/>
|
||||
</p>
|
||||
|
||||
Current G1 have 37 DOFs:
|
||||
As shown, there are a total of 4 versions of MJCF/URDF for the G1 robot:
|
||||
|
||||
```text
|
||||
root [⚓] => /pelvis/
|
||||
left_hip_pitch_joint [⚙+Y] => /left_hip_pitch_link/
|
||||
left_hip_roll_joint [⚙+X] => /left_hip_roll_link/
|
||||
left_hip_yaw_joint [⚙+Z] => /left_hip_yaw_link/
|
||||
left_knee_joint [⚙+Y] => /left_knee_link/
|
||||
left_ankle_pitch_joint [⚙+Y] => /left_ankle_pitch_link/
|
||||
left_ankle_roll_joint [⚙+X] => /left_ankle_roll_link/
|
||||
right_hip_pitch_joint [⚙+Y] => /right_hip_pitch_link/
|
||||
right_hip_roll_joint [⚙+X] => /right_hip_roll_link/
|
||||
right_hip_yaw_joint [⚙+Z] => /right_hip_yaw_link/
|
||||
right_knee_joint [⚙+Y] => /right_knee_link/
|
||||
right_ankle_pitch_joint [⚙+Y] => /right_ankle_pitch_link/
|
||||
right_ankle_roll_joint [⚙+X] => /right_ankle_roll_link/
|
||||
torso_joint [⚙+Z] => /torso_link/
|
||||
left_shoulder_pitch_joint [⚙+Y] => /left_shoulder_pitch_link/
|
||||
left_shoulder_roll_joint [⚙+X] => /left_shoulder_roll_link/
|
||||
left_shoulder_yaw_joint [⚙+Z] => /left_shoulder_yaw_link/
|
||||
left_elbow_pitch_joint [⚙+Y] => /left_elbow_pitch_link/
|
||||
left_elbow_roll_joint [⚙+X] => /left_elbow_roll_link/
|
||||
left_palm_joint [⚓] => /left_palm_link/
|
||||
left_zero_joint [⚙+Y] => /left_zero_link/
|
||||
left_one_joint [⚙+Z] => /left_one_link/
|
||||
left_two_joint [⚙+Z] => /left_two_link/
|
||||
left_three_joint [⚙+Z] => /left_three_link/
|
||||
left_four_joint [⚙+Z] => /left_four_link/
|
||||
left_five_joint [⚙+Z] => /left_five_link/
|
||||
left_six_joint [⚙+Z] => /left_six_link/
|
||||
right_shoulder_pitch_joint [⚙+Y] => /right_shoulder_pitch_link/
|
||||
right_shoulder_roll_joint [⚙+X] => /right_shoulder_roll_link/
|
||||
right_shoulder_yaw_joint [⚙+Z] => /right_shoulder_yaw_link/
|
||||
right_elbow_pitch_joint [⚙+Y] => /right_elbow_pitch_link/
|
||||
right_elbow_roll_joint [⚙+X] => /right_elbow_roll_link/
|
||||
right_palm_joint [⚓] => /right_palm_link/
|
||||
right_zero_joint [⚙+Y] => /right_zero_link/
|
||||
right_one_joint [⚙+Z] => /right_one_link/
|
||||
right_two_joint [⚙+Z] => /right_two_link/
|
||||
right_three_joint [⚙+Z] => /right_three_link/
|
||||
right_four_joint [⚙+Z] => /right_four_link/
|
||||
right_five_joint [⚙+Z] => /right_five_link/
|
||||
right_six_joint [⚙+Z] => /right_six_link/
|
||||
imu_joint [⚓] => /imu_link/
|
||||
```
|
||||
* `g1_23dof`
|
||||
* `g1_29dof`
|
||||
* `g1_29dof_with_hand`
|
||||
* `g1_dual_arm`
|
||||
|
||||
## Visulization with [MuJoCo](https://github.com/google-deepmind/mujoco)
|
||||
|
||||
|
@ -63,4 +27,4 @@ root [⚓] => /pelvis/
|
|||
python -m mujoco.viewer
|
||||
```
|
||||
|
||||
2. Drag and drop the MJCF model file (`scene.xml`) to the MuJoCo Viewer.
|
||||
2. Drag and drop the MJCF/URDF model file (`g1_XXX.xml`/`g1_XXX.urdf`) to the MuJoCo Viewer.
|
||||
|
|
|
@ -1,125 +0,0 @@
|
|||
g1_gazebo:
|
||||
# Publish all joint states -----------------------------------
|
||||
joint_state_controller:
|
||||
type: joint_state_controller/JointStateController
|
||||
publish_rate: 1000
|
||||
|
||||
torso_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: torso_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
# left leg Controllers ---------------------------------------
|
||||
left_hip_pitch_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_hip_pitch_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_hip_roll_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_hip_roll_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_hip_yaw_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_hip_yaw_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_knee_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_knee_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_ankle_pitch_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_ankle_pitch_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_ankle_roll_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_ankle_roll_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
# right leg Controllers ---------------------------------------
|
||||
right_hip_pitch_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_hip_pitch_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_hip_roll_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_hip_roll_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_hip_yaw_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_hip_yaw_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_knee_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_knee_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_ankle_pitch_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_ankle_pitch_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_ankle_roll_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_ankle_roll_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
|
||||
# left arm Controllers ---------------------------------------
|
||||
left_shoulder_pitch_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_shoulder_pitch_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_shoulder_roll_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_shoulder_roll_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_shoulder_yaw_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_shoulder_yaw_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_elbow_pitch_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_elbow_pitch_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
left_elbow_roll_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: left_elbow_roll_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
# right arm Controllers ---------------------------------------
|
||||
right_shoulder_pitch_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_shoulder_pitch_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_shoulder_roll_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_shoulder_roll_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_shoulder_yaw_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_shoulder_yaw_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_elbow_pitch_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_elbow_pitch_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
right_elbow_roll_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: right_elbow_roll_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
Binary file not shown.
Before Width: | Height: | Size: 403 KiB |
File diff suppressed because it is too large
Load Diff
|
@ -1,334 +0,0 @@
|
|||
<mujoco model="g1">
|
||||
<compiler angle="radian" meshdir="meshes/" autolimits="true" discardvisual="false"/>
|
||||
<statistic meansize="0.144785" extent="1.23314" center="0.025392 2.0634e-05 -0.245975"/>
|
||||
<default>
|
||||
<joint damping="0.5" armature="0.01" frictionloss="0.1"/>
|
||||
</default>
|
||||
<asset>
|
||||
<mesh name="pelvis" file="pelvis.STL"/>
|
||||
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||
<mesh name="torso_link" file="torso_link.STL"/>
|
||||
<mesh name="head_link" file="head_link.STL"/>
|
||||
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||
<mesh name="left_elbow_pitch_link" file="left_elbow_pitch_link.STL"/>
|
||||
<mesh name="left_elbow_roll_link" file="left_elbow_roll_link.STL"/>
|
||||
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||
<mesh name="right_elbow_pitch_link" file="right_elbow_pitch_link.STL"/>
|
||||
<mesh name="right_elbow_roll_link" file="right_elbow_roll_link.STL"/>
|
||||
<mesh name="logo_link" file="logo_link.STL"/>
|
||||
<mesh name="left_palm_link" file="left_palm_link.STL"/>
|
||||
<mesh name="left_zero_link" file="left_zero_link.STL"/>
|
||||
<mesh name="left_one_link" file="left_one_link.STL"/>
|
||||
<mesh name="left_two_link" file="left_two_link.STL"/>
|
||||
<mesh name="left_three_link" file="left_three_link.STL"/>
|
||||
<mesh name="left_four_link" file="left_four_link.STL"/>
|
||||
<mesh name="left_five_link" file="left_five_link.STL"/>
|
||||
<mesh name="left_six_link" file="left_six_link.STL"/>
|
||||
<mesh name="right_palm_link" file="right_palm_link.STL"/>
|
||||
<mesh name="right_zero_link" file="right_zero_link.STL"/>
|
||||
<mesh name="right_one_link" file="right_one_link.STL"/>
|
||||
<mesh name="right_two_link" file="right_two_link.STL"/>
|
||||
<mesh name="right_three_link" file="right_three_link.STL"/>
|
||||
<mesh name="right_four_link" file="right_four_link.STL"/>
|
||||
<mesh name="right_five_link" file="right_five_link.STL"/>
|
||||
<mesh name="right_six_link" file="right_six_link.STL"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<body name="pelvis" pos="0 0 0.755">
|
||||
<inertial pos="0 0 -0.07605" quat="1 0 -0.000405289 0" mass="2.86" diaginertia="0.0079143 0.0069837 0.0059404"/>
|
||||
<joint name="floating_base_joint" type="free"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis_contour_link"/>
|
||||
<body name="left_hip_pitch_link" pos="0 0.06445 -0.1027" quat="0.984807 0 -0.17365 0">
|
||||
<inertial pos="0.001962 0.049392 -0.000941" quat="0.420735 0.907025 -0.0155675 -0.00670646" mass="1.299" diaginertia="0.00138785 0.000955478 0.00086947"/>
|
||||
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.35 3.05"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||
<body name="left_hip_roll_link" pos="0 0.0523 0">
|
||||
<inertial pos="0.024757 -0.001036 -0.086323" quat="0.977498 -0.00692636 0.210181 0.0165269" mass="1.446" diaginertia="0.00244106 0.00230425 0.00142899"/>
|
||||
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.26 2.53"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||
<body name="left_hip_yaw_link" pos="0.01966 -0.0012139 -0.1241">
|
||||
<inertial pos="-0.053554 -0.011477 -0.14067" quat="0.645099 0.15885 0.202109 0.71956" mass="2.052" diaginertia="0.0114475 0.0107868 0.00214501"/>
|
||||
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.75 2.75"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||
<body name="left_knee_link" pos="-0.078292 -0.0017335 -0.177225" quat="0.967714 0 0.252052 0">
|
||||
<inertial pos="0.005505 0.006534 -0.116629" quat="0.799234 -0.0128894 0.0354278 0.599836" mass="2.252" diaginertia="0.0127418 0.0124382 0.00192524"/>
|
||||
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.33489 2.5449"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||
<geom size="0.015 0.075" pos="0.007 0.005 -0.15" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_ankle_pitch_link" pos="0 0.0040687 -0.30007" quat="0.99678 0 -0.0801788 0">
|
||||
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.68 0.73"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||
<inertial pos="0.024762 2e-05 -0.012526" quat="0.000771333 0.734476 0.000921291 0.678634" mass="0.391" diaginertia="0.00110394 0.0010657 0.000149255"/>
|
||||
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||
<geom size="0.001" pos="-0.06 0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.001" pos="-0.06 -0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.001" pos="0.13 0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.001" pos="0.13 -0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_hip_pitch_link" pos="0 -0.06445 -0.1027" quat="0.984807 0 -0.17365 0">
|
||||
<inertial pos="0.001962 -0.049392 -0.000941" quat="0.907025 0.420735 0.00670646 0.0155675" mass="1.299" diaginertia="0.00138785 0.000955478 0.00086947"/>
|
||||
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.35 3.05"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||
<body name="right_hip_roll_link" pos="0 -0.0523 0">
|
||||
<inertial pos="0.024757 0.001036 -0.086323" quat="0.977498 0.00692636 0.210181 -0.0165269" mass="1.446" diaginertia="0.00244106 0.00230425 0.00142899"/>
|
||||
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.53 0.26"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||
<body name="right_hip_yaw_link" pos="0.01966 0.0012139 -0.1241">
|
||||
<inertial pos="-0.053554 0.011477 -0.14067" quat="0.71956 0.202109 0.15885 0.645099" mass="2.052" diaginertia="0.0114475 0.0107868 0.00214501"/>
|
||||
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.75 2.75"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||
<body name="right_knee_link" pos="-0.078292 0.0017335 -0.177225" quat="0.967714 0 0.252052 0">
|
||||
<inertial pos="0.005505 -0.006534 -0.116629" quat="0.599836 0.0354278 -0.0128894 0.799234" mass="2.252" diaginertia="0.0127418 0.0124382 0.00192524"/>
|
||||
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.33489 2.5449"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||
<geom size="0.015 0.075" pos="0.007 -0.005 -0.15" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_ankle_pitch_link" pos="0 -0.0040687 -0.30007" quat="0.99678 0 -0.0801788 0">
|
||||
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.68 0.73"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||
<inertial pos="0.024762 -2e-05 -0.012526" quat="-0.000771333 0.734476 -0.000921291 0.678634" mass="0.391" diaginertia="0.00110394 0.0010657 0.000149255"/>
|
||||
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||
<geom size="0.001" pos="-0.06 0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.001" pos="-0.06 -0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.001" pos="0.13 0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.001" pos="0.13 -0.02 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="torso_link">
|
||||
<inertial pos="0.00187791 0.00229457 0.208747" quat="0.999957 0.00624375 -0.00636707 -0.0026338" mass="7.52036" diaginertia="0.12848 0.111753 0.0350394"/>
|
||||
<joint name="torso_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<body name="left_shoulder_pitch_link" pos="-0.0025 0.10396 0.25928" quat="0.990268 0.139172 0 0">
|
||||
<inertial pos="-0.001431 0.048811 0.001304" quat="0.786417 0.588396 -0.180543 0.0523639" mass="0.713" diaginertia="0.000466421 0.000440181 0.000410999"/>
|
||||
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.9671 2.7925"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||
<body name="left_shoulder_roll_link" pos="0 0.052 0" quat="0.990268 -0.139172 0 0">
|
||||
<inertial pos="-0.003415 0.006955 -0.064598" quat="0.70683 0.0105364 0.00575207 0.707282" mass="0.642" diaginertia="0.000683514 0.000616029 0.000372857"/>
|
||||
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_yaw_link" pos="-0.00354 0.0062424 -0.1032">
|
||||
<inertial pos="0.000375 -0.00444 -0.072374" quat="0.903834 -0.0374183 0.00985482 0.42613" mass="0.713" diaginertia="0.000977874 0.000964661 0.000379065"/>
|
||||
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<body name="left_elbow_pitch_link" pos="0 0.00189 -0.0855">
|
||||
<inertial pos="0.064497 0.002873 0" quat="0.582347 0.582495 0.400893 0.401069" mass="0.601" diaginertia="0.00049549 0.0004712 0.00025371"/>
|
||||
<joint name="left_elbow_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.2268 3.4208"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_pitch_link"/>
|
||||
<body name="left_elbow_roll_link" pos="0.1 0 0">
|
||||
<inertial pos="0.133814 0.00147121 0.000265832" quat="0.496781 0.497877 0.498782 0.506502" mass="0.50826" diaginertia="0.00239763 0.00226639 0.000285577"/>
|
||||
<joint name="left_elbow_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.0943 2.0943"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_roll_link"/>
|
||||
<geom pos="0.12 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_palm_link"/>
|
||||
<geom pos="0.12 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_palm_link"/>
|
||||
<body name="left_zero_link" pos="0.17 0 0">
|
||||
<inertial pos="-0.0260466 -0.00877511 1.08605e-05" quat="0.59241 0.381376 -0.592953 0.389884" mass="0.0509893" diaginertia="8.68047e-06 7.23365e-06 4.58058e-06"/>
|
||||
<joint name="left_zero_joint" pos="0 0 0" axis="0 1 0" range="-0.523598 0.523598"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_zero_link"/>
|
||||
<body name="left_one_link" pos="-0.026525 -0.0188 -5e-05">
|
||||
<inertial pos="-0.00181538 -0.0327057 -0.000185871" quat="0.701646 0.698199 0.0817825 -0.116289" mass="0.047762" diaginertia="8.03051e-06 7.8455e-06 3.65282e-06"/>
|
||||
<joint name="left_one_joint" pos="0 0 0" axis="0 0 1" range="-1 1.2"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_one_link"/>
|
||||
<geom size="0.01 0.015 0.01" pos="-0.001 -0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_two_link" pos="0 -0.0431 0">
|
||||
<inertial pos="-0.00135257 -0.0237591 -0.000119669" quat="0.717995 0.695316 -0.0180122 -0.0263741" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
|
||||
<joint name="left_two_joint" pos="0 0 0" axis="0 0 1" range="0 1.84"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_two_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_two_link"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_three_link" pos="0.205 0.004 0.02395">
|
||||
<inertial pos="0.0362561 -0.0015725 0.000269899" quat="0.540443 0.459072 0.5397 0.45376" mass="0.0488469" diaginertia="8.91742e-06 8.64873e-06 3.8319e-06"/>
|
||||
<joint name="left_three_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0.3"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_three_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_three_link"/>
|
||||
<body name="left_four_link" pos="0.0471 -0.0036 0">
|
||||
<inertial pos="0.0237591 0.00135257 0.000119669" quat="0.478926 0.48905 0.526348 0.504399" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
|
||||
<joint name="left_four_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_four_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_four_link"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_five_link" pos="0.205 0.004 -0.02395">
|
||||
<inertial pos="0.0362561 -0.0015725 0.000269899" quat="0.540443 0.459072 0.5397 0.45376" mass="0.0488469" diaginertia="8.91742e-06 8.64873e-06 3.8319e-06"/>
|
||||
<joint name="left_five_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0.3"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_five_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_five_link"/>
|
||||
<body name="left_six_link" pos="0.0471 -0.0036 0">
|
||||
<inertial pos="0.0237591 0.00135257 0.000119669" quat="0.478926 0.48905 0.526348 0.504399" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
|
||||
<joint name="left_six_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_six_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_six_link"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_shoulder_pitch_link" pos="-0.0025 -0.10396 0.25928" quat="0.990268 -0.139172 0 0">
|
||||
<inertial pos="-0.001431 -0.048811 0.001304" quat="0.588396 0.786417 -0.0523639 0.180543" mass="0.713" diaginertia="0.000466421 0.000440181 0.000410999"/>
|
||||
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.9671 2.7925"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||
<body name="right_shoulder_roll_link" pos="0 -0.052 0" quat="0.990268 0.139172 0 0">
|
||||
<inertial pos="-0.003415 -0.006955 -0.064598" quat="0.707282 0.00575207 0.0105364 0.70683" mass="0.642" diaginertia="0.000683514 0.000616029 0.000372857"/>
|
||||
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_yaw_link" pos="-0.00354 -0.0062424 -0.1032">
|
||||
<inertial pos="0.000375 0.00444 -0.072374" quat="0.42613 0.00985482 -0.0374183 0.903834" mass="0.713" diaginertia="0.000977874 0.000964661 0.000379065"/>
|
||||
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<body name="right_elbow_pitch_link" pos="0 -0.00189 -0.0855">
|
||||
<inertial pos="0.064497 -0.002873 0" quat="0.401069 0.400893 0.582495 0.582347" mass="0.601" diaginertia="0.00049549 0.0004712 0.00025371"/>
|
||||
<joint name="right_elbow_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.2268 3.4208"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_pitch_link"/>
|
||||
<body name="right_elbow_roll_link" pos="0.1 0 0">
|
||||
<inertial pos="0.133814 -0.00147121 0.000265832" quat="0.506502 0.498782 0.497877 0.496781" mass="0.50826" diaginertia="0.00239763 0.00226639 0.000285577"/>
|
||||
<joint name="right_elbow_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.0943 2.0943"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_roll_link"/>
|
||||
<geom pos="0.12 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_palm_link"/>
|
||||
<geom pos="0.12 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_palm_link"/>
|
||||
<body name="right_zero_link" pos="0.17 0 0">
|
||||
<inertial pos="-0.0260466 0.00877511 1.08605e-05" quat="0.381376 0.59241 -0.389884 0.592953" mass="0.0509893" diaginertia="8.68047e-06 7.23365e-06 4.58058e-06"/>
|
||||
<joint name="right_zero_joint" pos="0 0 0" axis="0 1 0" range="-0.523598 0.523598"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_zero_link"/>
|
||||
<body name="right_one_link" pos="-0.026525 0.0188 -5e-05">
|
||||
<inertial pos="-0.00181538 0.0327057 -0.000185871" quat="0.698199 0.701646 0.116289 -0.0817825" mass="0.047762" diaginertia="8.03051e-06 7.8455e-06 3.65282e-06"/>
|
||||
<joint name="right_one_joint" pos="0 0 0" axis="0 0 1" range="-1.2 1"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_one_link"/>
|
||||
<geom size="0.01 0.015 0.01" pos="-0.001 0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_two_link" pos="0 0.0431 0">
|
||||
<inertial pos="-0.00135257 0.0237591 -0.000119669" quat="0.695316 0.717995 0.0263741 0.0180122" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
|
||||
<joint name="right_two_joint" pos="0 0 0" axis="0 0 1" range="-1.84 0"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_two_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_two_link"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_three_link" pos="0.205 -0.004 0.02395">
|
||||
<inertial pos="0.0362561 0.0015725 0.000269899" quat="0.45376 0.5397 0.459072 0.540443" mass="0.0488469" diaginertia="8.91742e-06 8.64873e-06 3.8319e-06"/>
|
||||
<joint name="right_three_joint" pos="0 0 0" axis="0 0 1" range="-0.3 1.84"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_three_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_three_link"/>
|
||||
<body name="right_four_link" pos="0.0471 0.0036 0">
|
||||
<inertial pos="0.0237591 -0.00135257 0.000119669" quat="0.504399 0.526348 0.48905 0.478926" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
|
||||
<joint name="right_four_joint" pos="0 0 0" axis="0 0 1" range="0 1.84"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_four_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_four_link"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_five_link" pos="0.205 -0.004 -0.02395">
|
||||
<inertial pos="0.0362561 0.0015725 0.000269899" quat="0.45376 0.5397 0.459072 0.540443" mass="0.0488469" diaginertia="8.91742e-06 8.64873e-06 3.8319e-06"/>
|
||||
<joint name="right_five_joint" pos="0 0 0" axis="0 0 1" range="-0.3 1.84"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_five_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_five_link"/>
|
||||
<body name="right_six_link" pos="0.0471 0.0036 0">
|
||||
<inertial pos="0.0237591 -0.00135257 0.000119669" quat="0.504399 0.526348 0.48905 0.478926" mass="0.0138584" diaginertia="2.55338e-06 2.04399e-06 9.3995e-07"/>
|
||||
<joint name="right_six_joint" pos="0 0 0" axis="0 0 1" range="0 1.84"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_six_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_six_link"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint" ctrllimited="true" ctrlrange="-88 88"/>
|
||||
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint" ctrllimited="true" ctrlrange="-88 88"/>
|
||||
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint" ctrllimited="true" ctrlrange="-88 88"/>
|
||||
<motor name="left_knee_joint" joint="left_knee_joint" ctrllimited="true" ctrlrange="-139 139"/>
|
||||
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint" ctrllimited="true" ctrlrange="-40 40"/>
|
||||
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint" ctrllimited="true" ctrlrange="-40 40"/>
|
||||
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint" ctrllimited="true" ctrlrange="-88 88"/>
|
||||
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint" ctrllimited="true" ctrlrange="-88 88"/>
|
||||
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint" ctrllimited="true" ctrlrange="-88 88"/>
|
||||
<motor name="right_knee_joint" joint="right_knee_joint" ctrllimited="true" ctrlrange="-139 139"/>
|
||||
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint" ctrllimited="true" ctrlrange="-40 40"/>
|
||||
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint" ctrllimited="true" ctrlrange="-40 40"/>
|
||||
<motor name="torso_joint" joint="torso_joint" ctrllimited="true" ctrlrange="-88 88"/>
|
||||
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="left_elbow_pitch_joint" joint="left_elbow_pitch_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="left_elbow_roll_joint" joint="left_elbow_roll_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="right_elbow_pitch_joint" joint="right_elbow_pitch_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="right_elbow_roll_joint" joint="right_elbow_roll_joint" ctrllimited="true" ctrlrange="-20 20"/>
|
||||
<motor name="left_zero_joint" joint="left_zero_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="left_one_joint" joint="left_one_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="left_two_joint" joint="left_two_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="left_three_joint" joint="left_three_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="left_four_joint" joint="left_four_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="left_five_joint" joint="left_five_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="left_six_joint" joint="left_six_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="right_zero_joint" joint="right_zero_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="right_one_joint" joint="right_one_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="right_two_joint" joint="right_two_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="right_three_joint" joint="right_three_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="right_four_joint" joint="right_four_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="right_five_joint" joint="right_five_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
<motor name="right_six_joint" joint="right_six_joint" ctrllimited="true" ctrlrange="-0.7 0.7"/>
|
||||
</actuator>
|
||||
</mujoco>
|
|
@ -0,0 +1,880 @@
|
|||
<robot name="g1_23dof">
|
||||
<mujoco>
|
||||
<compiler meshdir="meshes" discardvisual="false"/>
|
||||
</mujoco>
|
||||
|
||||
<!-- [CAUTION] uncomment when convert to mujoco -->
|
||||
<!-- <link name="world"></link>
|
||||
<joint name="floating_base_joint" type="floating">
|
||||
<parent link="world"/>
|
||||
<child link="pelvis"/>
|
||||
</joint> -->
|
||||
|
||||
<link name="pelvis">
|
||||
<inertial>
|
||||
<origin xyz="0 0 -0.07605" rpy="0 0 0"/>
|
||||
<mass value="3.813"/>
|
||||
<inertia ixx="0.010549" ixy="0" ixz="2.1E-06" iyy="0.0093089" iyz="0" izz="0.0079184"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/pelvis.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="pelvis_contour_link">
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="0.001"/>
|
||||
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="pelvis_contour_joint" type="fixed">
|
||||
<parent link="pelvis"/>
|
||||
<child link="pelvis_contour_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- Legs -->
|
||||
<link name="left_hip_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="0.002741 0.047791 -0.02606" rpy="0 0 0"/>
|
||||
<mass value="1.35"/>
|
||||
<inertia ixx="0.001811" ixy="3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="0.000171" izz="0.0012812"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_hip_pitch_joint" type="revolute">
|
||||
<origin xyz="0 0.064452 -0.1027" rpy="0 0 0"/>
|
||||
<parent link="pelvis"/>
|
||||
<child link="left_hip_pitch_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||||
</joint>
|
||||
<link name="left_hip_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="0.029812 -0.001045 -0.087934" rpy="0 0 0"/>
|
||||
<mass value="1.52"/>
|
||||
<inertia ixx="0.0023773" ixy="-3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="1.84E-05" izz="0.0016595"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_hip_roll_joint" type="revolute">
|
||||
<origin xyz="0 0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||||
<parent link="left_hip_pitch_link"/>
|
||||
<child link="left_hip_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-0.5236" upper="2.9671" effort="88" velocity="32"/>
|
||||
</joint>
|
||||
<link name="left_hip_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.057709 -0.010981 -0.15078" rpy="0 0 0"/>
|
||||
<mass value="1.702"/>
|
||||
<inertia ixx="0.0057774" ixy="-0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="-0.0007072" izz="0.003149"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_hip_yaw_joint" type="revolute">
|
||||
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||||
<parent link="left_hip_roll_link"/>
|
||||
<child link="left_hip_yaw_link"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||||
</joint>
|
||||
<link name="left_knee_link">
|
||||
<inertial>
|
||||
<origin xyz="0.005457 0.003964 -0.12074" rpy="0 0 0"/>
|
||||
<mass value="1.932"/>
|
||||
<inertia ixx="0.011329" ixy="4.82E-05" ixz="-4.49E-05" iyy="0.011277" iyz="-0.0007146" izz="0.0015168"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_knee_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_knee_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_knee_joint" type="revolute">
|
||||
<origin xyz="-0.078273 0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||||
<parent link="left_hip_yaw_link"/>
|
||||
<child link="left_knee_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||||
</joint>
|
||||
<link name="left_ankle_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||||
<mass value="0.074"/>
|
||||
<inertia ixx="8.4E-06" ixy="0" ixz="-2.9E-06" iyy="1.89E-05" iyz="0" izz="1.26E-05"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_ankle_pitch_joint" type="revolute">
|
||||
<origin xyz="0 -9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||||
<parent link="left_knee_link"/>
|
||||
<child link="left_ankle_pitch_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||||
</joint>
|
||||
<link name="left_ankle_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||||
<mass value="0.608"/>
|
||||
<inertia ixx="0.0002231" ixy="2E-07" ixz="8.91E-05" iyy="0.0016161" iyz="-1E-07" izz="0.0016667"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_ankle_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.005"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.005"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.005"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.005"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_ankle_roll_joint" type="revolute">
|
||||
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||||
<parent link="left_ankle_pitch_link"/>
|
||||
<child link="left_ankle_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||||
</joint>
|
||||
<link name="right_hip_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="0.002741 -0.047791 -0.02606" rpy="0 0 0"/>
|
||||
<mass value="1.35"/>
|
||||
<inertia ixx="0.001811" ixy="-3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="-0.000171" izz="0.0012812"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_hip_pitch_joint" type="revolute">
|
||||
<origin xyz="0 -0.064452 -0.1027" rpy="0 0 0"/>
|
||||
<parent link="pelvis"/>
|
||||
<child link="right_hip_pitch_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||||
</joint>
|
||||
<link name="right_hip_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="0.029812 0.001045 -0.087934" rpy="0 0 0"/>
|
||||
<mass value="1.52"/>
|
||||
<inertia ixx="0.0023773" ixy="3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="-1.84E-05" izz="0.0016595"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_hip_roll_joint" type="revolute">
|
||||
<origin xyz="0 -0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||||
<parent link="right_hip_pitch_link"/>
|
||||
<child link="right_hip_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-2.9671" upper="0.5236" effort="88" velocity="32"/>
|
||||
</joint>
|
||||
<link name="right_hip_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.057709 0.010981 -0.15078" rpy="0 0 0"/>
|
||||
<mass value="1.702"/>
|
||||
<inertia ixx="0.0057774" ixy="0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="0.0007072" izz="0.003149"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_hip_yaw_joint" type="revolute">
|
||||
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||||
<parent link="right_hip_roll_link"/>
|
||||
<child link="right_hip_yaw_link"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||||
</joint>
|
||||
<link name="right_knee_link">
|
||||
<inertial>
|
||||
<origin xyz="0.005457 -0.003964 -0.12074" rpy="0 0 0"/>
|
||||
<mass value="1.932"/>
|
||||
<inertia ixx="0.011329" ixy="-4.82E-05" ixz="4.49E-05" iyy="0.011277" iyz="0.0007146" izz="0.0015168"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_knee_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_knee_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_knee_joint" type="revolute">
|
||||
<origin xyz="-0.078273 -0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||||
<parent link="right_hip_yaw_link"/>
|
||||
<child link="right_knee_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||||
</joint>
|
||||
<link name="right_ankle_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||||
<mass value="0.074"/>
|
||||
<inertia ixx="8.4E-06" ixy="0" ixz="-2.9E-06" iyy="1.89E-05" iyz="0" izz="1.26E-05"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_ankle_pitch_joint" type="revolute">
|
||||
<origin xyz="0 9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||||
<parent link="right_knee_link"/>
|
||||
<child link="right_ankle_pitch_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||||
</joint>
|
||||
<link name="right_ankle_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||||
<mass value="0.608"/>
|
||||
<inertia ixx="0.0002231" ixy="-2E-07" ixz="8.91E-05" iyy="0.0016161" iyz="1E-07" izz="0.0016667"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_ankle_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.005"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.005"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.005"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.005"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_ankle_roll_joint" type="revolute">
|
||||
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||||
<parent link="right_ankle_pitch_link"/>
|
||||
<child link="right_ankle_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||||
</joint>
|
||||
|
||||
<!-- Torso -->
|
||||
<link name="waist_yaw_fixed_link">
|
||||
<inertial>
|
||||
<origin xyz="0.003964 0 0.018769" rpy="0 0 0"/>
|
||||
<mass value="0.244"/>
|
||||
<inertia ixx="9.9587E-05" ixy="-1.833E-06" ixz="-1.2617E-05" iyy="0.00012411" iyz="-1.18E-07" izz="0.00015586"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/waist_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="waist_yaw_fixed_joint" type="fixed">
|
||||
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="waist_yaw_fixed_link"/>
|
||||
</joint>
|
||||
<joint name="waist_yaw_joint" type="revolute">
|
||||
<origin xyz="-0.0039635 0 0.054" rpy="0 0 0"/>
|
||||
<parent link="pelvis"/>
|
||||
<child link="torso_link"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.618" upper="2.618" effort="88" velocity="32"/>
|
||||
</joint>
|
||||
<link name="torso_link">
|
||||
<inertial>
|
||||
<origin xyz="0.002601 0.000257 0.153719" rpy="0 0 0"/>
|
||||
<mass value="8.562"/>
|
||||
<inertia ixx="0.065674966" ixy="-8.597E-05" ixz="-0.001737252" iyy="0.053535188" iyz="8.6899E-05" izz="0.030808125"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/torso_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/torso_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!-- LOGO -->
|
||||
<joint name="logo_joint" type="fixed">
|
||||
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="logo_link"/>
|
||||
</joint>
|
||||
<link name="logo_link">
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="0.001"/>
|
||||
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/logo_link.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/logo_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!-- Head -->
|
||||
<link name="head_link">
|
||||
<inertial>
|
||||
<origin xyz="0.005267 0.000299 0.449869" rpy="0 0 0"/>
|
||||
<mass value="1.036"/>
|
||||
<inertia ixx="0.004085051" ixy="-2.543E-06" ixz="-6.9455E-05" iyy="0.004185212" iyz="-3.726E-06" izz="0.001807911"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/head_link.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/head_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="head_joint" type="fixed">
|
||||
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="head_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- Waist Support -->
|
||||
<link name="waist_support_link">
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="0.001"/>
|
||||
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/waist_support_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/waist_support_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="waist_support_joint" type="fixed">
|
||||
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="waist_support_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<origin xyz="-0.03959 -0.00224 0.13792" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="imu_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- Arm -->
|
||||
<link name="left_shoulder_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="0 0.035892 -0.011628" rpy="0 0 0"/>
|
||||
<mass value="0.718"/>
|
||||
<inertia ixx="0.0004291" ixy="-9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="2.26E-05" izz="0.000423"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_shoulder_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_shoulder_pitch_joint" type="revolute">
|
||||
<origin xyz="0.0039563 0.10022 0.23778" rpy="0.27931 5.4949E-05 -0.00019159"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="left_shoulder_pitch_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="left_shoulder_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.000227 0.00727 -0.063243" rpy="0 0 0"/>
|
||||
<mass value="0.643"/>
|
||||
<inertia ixx="0.0006177" ixy="-1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="-5.3E-06" izz="0.0003894"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_shoulder_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.004 0.006 -0.053" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_shoulder_roll_joint" type="revolute">
|
||||
<origin xyz="0 0.038 -0.013831" rpy="-0.27925 0 0"/>
|
||||
<parent link="left_shoulder_pitch_link"/>
|
||||
<child link="left_shoulder_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-1.5882" upper="2.2515" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="left_shoulder_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="0.010773 -0.002949 -0.072009" rpy="0 0 0"/>
|
||||
<mass value="0.734"/>
|
||||
<inertia ixx="0.0009988" ixy="7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="-2.86E-05" izz="0.0004354"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_shoulder_yaw_joint" type="revolute">
|
||||
<origin xyz="0 0.00624 -0.1032" rpy="0 0 0"/>
|
||||
<parent link="left_shoulder_roll_link"/>
|
||||
<child link="left_shoulder_yaw_link"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="left_elbow_link">
|
||||
<inertial>
|
||||
<origin xyz="0.064956 0.004454 -0.010062" rpy="0 0 0"/>
|
||||
<mass value="0.6"/>
|
||||
<inertia ixx="0.0002891" ixy="6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="-5.6E-06" izz="0.0004197"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_elbow_joint" type="revolute">
|
||||
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||
<parent link="left_shoulder_yaw_link"/>
|
||||
<child link="left_elbow_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<joint name="left_wrist_roll_joint" type="revolute">
|
||||
<origin xyz="0.100 0.00188791 -0.010" rpy="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="left_elbow_link"/>
|
||||
<child link="left_wrist_roll_rubber_hand"/>
|
||||
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||
</joint>
|
||||
<link name="left_wrist_roll_rubber_hand">
|
||||
<inertial>
|
||||
<origin xyz="0.10794656650 0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||||
<mass value="0.35692864"/>
|
||||
<inertia ixx="0.00019613494735" ixy="-0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="0.00000249774203" izz="0.00194181412808"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="right_shoulder_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="0 -0.035892 -0.011628" rpy="0 0 0"/>
|
||||
<mass value="0.718"/>
|
||||
<inertia ixx="0.0004291" ixy="9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="-2.26E-05" izz="0.000423"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_shoulder_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 -0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_shoulder_pitch_joint" type="revolute">
|
||||
<origin xyz="0.0039563 -0.10021 0.23778" rpy="-0.27931 5.4949E-05 0.00019159"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="right_shoulder_pitch_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="right_shoulder_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.000227 -0.00727 -0.063243" rpy="0 0 0"/>
|
||||
<mass value="0.643"/>
|
||||
<inertia ixx="0.0006177" ixy="1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="5.3E-06" izz="0.0003894"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_shoulder_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.004 -0.006 -0.053" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_shoulder_roll_joint" type="revolute">
|
||||
<origin xyz="0 -0.038 -0.013831" rpy="0.27925 0 0"/>
|
||||
<parent link="right_shoulder_pitch_link"/>
|
||||
<child link="right_shoulder_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-2.2515" upper="1.5882" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="right_shoulder_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="0.010773 0.002949 -0.072009" rpy="0 0 0"/>
|
||||
<mass value="0.734"/>
|
||||
<inertia ixx="0.0009988" ixy="-7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="2.86E-05" izz="0.0004354"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_shoulder_yaw_joint" type="revolute">
|
||||
<origin xyz="0 -0.00624 -0.1032" rpy="0 0 0"/>
|
||||
<parent link="right_shoulder_roll_link"/>
|
||||
<child link="right_shoulder_yaw_link"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="right_elbow_link">
|
||||
<inertial>
|
||||
<origin xyz="0.064956 -0.004454 -0.010062" rpy="0 0 0"/>
|
||||
<mass value="0.6"/>
|
||||
<inertia ixx="0.0002891" ixy="-6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="5.6E-06" izz="0.0004197"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_elbow_joint" type="revolute">
|
||||
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||
<parent link="right_shoulder_yaw_link"/>
|
||||
<child link="right_elbow_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<joint name="right_wrist_roll_joint" type="revolute">
|
||||
<origin xyz="0.100 -0.00188791 -0.010" rpy="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="right_elbow_link"/>
|
||||
<child link="right_wrist_roll_rubber_hand"/>
|
||||
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||
</joint>
|
||||
<link name="right_wrist_roll_rubber_hand">
|
||||
<inertial>
|
||||
<origin xyz="0.10794656650 -0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||||
<mass value="0.35692864"/>
|
||||
<inertia ixx="0.00019613494735" ixy="0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="-0.00000249774203" izz="0.00194181412808"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
|
@ -0,0 +1,246 @@
|
|||
<mujoco model="g1_23dof">
|
||||
<compiler angle="radian" meshdir="meshes"/>
|
||||
|
||||
<asset>
|
||||
<mesh name="pelvis" file="pelvis.STL"/>
|
||||
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||
<mesh name="torso_link" file="torso_link.STL"/>
|
||||
<mesh name="logo_link" file="logo_link.STL"/>
|
||||
<mesh name="head_link" file="head_link.STL"/>
|
||||
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||
<mesh name="left_wrist_roll_rubber_hand" file="left_wrist_roll_rubber_hand.STL"/>
|
||||
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||
<mesh name="right_wrist_roll_rubber_hand" file="right_wrist_roll_rubber_hand.STL"/>
|
||||
</asset>
|
||||
|
||||
<worldbody>
|
||||
<body name="pelvis" pos="0 0 0.793">
|
||||
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="torso_link" pos="-0.0039635 0 0.054">
|
||||
<inertial pos="0.0034309 0.00025505 0.174524" quat="0.99988 0.000261157 0.0149809 -0.0038211" mass="9.842" diaginertia="0.135151 0.123088 0.0327256"/>
|
||||
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||
<site name="imu" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.23778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||
<body name="left_wrist_roll_rubber_hand" pos="0.1 0.00188791 -0.01">
|
||||
<inertial pos="0.107947 0.00163512 0.00202245" quat="0.494051 0.504265 0.48416 0.516933" mass="0.356929" diaginertia="0.00200292 0.0019426 0.000195232"/>
|
||||
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_rubber_hand"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_rubber_hand"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.23778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||
<body name="right_wrist_roll_rubber_hand" pos="0.1 -0.00188791 -0.01">
|
||||
<inertial pos="0.107947 -0.00163512 0.00202245" quat="0.516933 0.48416 0.504265 0.494051" mass="0.356929" diaginertia="0.00200292 0.0019426 0.000195232"/>
|
||||
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_rubber_hand"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_rubber_hand"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
</sensor>
|
||||
|
||||
|
||||
<!-- setup scene -->
|
||||
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||
<visual>
|
||||
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||
<rgba haze="0.15 0.25 0.35 1"/>
|
||||
<global azimuth="-140" elevation="-20"/>
|
||||
</visual>
|
||||
<asset>
|
||||
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||
</worldbody>
|
||||
</mujoco>
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,294 @@
|
|||
<mujoco model="g1_29dof">
|
||||
<compiler angle="radian" meshdir="meshes"/>
|
||||
|
||||
<asset>
|
||||
<mesh name="pelvis" file="pelvis.STL"/>
|
||||
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||
<mesh name="waist_roll_link" file="waist_roll_link.STL"/>
|
||||
<mesh name="torso_link" file="torso_link.STL"/>
|
||||
<mesh name="logo_link" file="logo_link.STL"/>
|
||||
<mesh name="head_link" file="head_link.STL"/>
|
||||
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||
<mesh name="left_rubber_hand" file="left_rubber_hand.STL"/>
|
||||
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||
<mesh name="right_rubber_hand" file="right_rubber_hand.STL"/>
|
||||
</asset>
|
||||
|
||||
<worldbody>
|
||||
<body name="pelvis" pos="0 0 0.793">
|
||||
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="waist_yaw_link">
|
||||
<inertial pos="0.003964 0 0.018769" quat="-0.0178291 0.628464 0.0282471 0.777121" mass="0.244" diaginertia="0.000158561 0.000124229 9.67669e-05"/>
|
||||
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||
<body name="waist_roll_link" pos="-0.0039635 0 0.035">
|
||||
<inertial pos="0 -0.000236 0.010111" quat="0.99979 0.020492 0 0" mass="0.047" diaginertia="7.515e-06 6.40206e-06 3.98394e-06"/>
|
||||
<joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||
<body name="torso_link" pos="0 0 0.019">
|
||||
<inertial pos="0.00331658 0.000261533 0.179856" quat="0.999831 0.000376204 0.0179895 -0.00377704" mass="9.598" diaginertia="0.12407 0.111951 0.0325382"/>
|
||||
<joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||
<site name="imu" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.23778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||
<inertial pos="0.0708244 0.000191745 0.00161742" quat="0.510571 0.526295 0.468078 0.493188" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_rubber_hand"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.23778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||
<inertial pos="0.0708244 -0.000191745 0.00161742" quat="0.493188 0.468078 0.526295 0.510571" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_rubber_hand"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||
<motor name="waist_roll_joint" joint="waist_roll_joint"/>
|
||||
<motor name="waist_pitch_joint" joint="waist_pitch_joint"/>
|
||||
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
</sensor>
|
||||
|
||||
|
||||
<!-- setup scene -->
|
||||
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||
<visual>
|
||||
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||
<rgba haze="0.15 0.25 0.35 1"/>
|
||||
<global azimuth="-140" elevation="-20"/>
|
||||
</visual>
|
||||
<asset>
|
||||
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||
</worldbody>
|
||||
</mujoco>
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,408 @@
|
|||
<mujoco model="g1_29dof_with_hand">
|
||||
<compiler angle="radian" meshdir="meshes"/>
|
||||
|
||||
<asset>
|
||||
<mesh name="pelvis" file="pelvis.STL"/>
|
||||
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||
<mesh name="waist_roll_link" file="waist_roll_link.STL"/>
|
||||
<mesh name="torso_link" file="torso_link.STL"/>
|
||||
<mesh name="logo_link" file="logo_link.STL"/>
|
||||
<mesh name="head_link" file="head_link.STL"/>
|
||||
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||
<mesh name="left_hand_palm_link" file="left_hand_palm_link.STL"/>
|
||||
<mesh name="left_hand_zero_link" file="left_hand_zero_link.STL"/>
|
||||
<mesh name="left_hand_one_link" file="left_hand_one_link.STL"/>
|
||||
<mesh name="left_hand_two_link" file="left_hand_two_link.STL"/>
|
||||
<mesh name="left_hand_three_link" file="left_hand_three_link.STL"/>
|
||||
<mesh name="left_hand_four_link" file="left_hand_four_link.STL"/>
|
||||
<mesh name="left_hand_five_link" file="left_hand_five_link.STL"/>
|
||||
<mesh name="left_hand_six_link" file="left_hand_six_link.STL"/>
|
||||
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||
<mesh name="right_hand_palm_link" file="right_hand_palm_link.STL"/>
|
||||
<mesh name="right_hand_zero_link" file="right_hand_zero_link.STL"/>
|
||||
<mesh name="right_hand_one_link" file="right_hand_one_link.STL"/>
|
||||
<mesh name="right_hand_two_link" file="right_hand_two_link.STL"/>
|
||||
<mesh name="right_hand_three_link" file="right_hand_three_link.STL"/>
|
||||
<mesh name="right_hand_four_link" file="right_hand_four_link.STL"/>
|
||||
<mesh name="right_hand_five_link" file="right_hand_five_link.STL"/>
|
||||
<mesh name="right_hand_six_link" file="right_hand_six_link.STL"/>
|
||||
</asset>
|
||||
|
||||
<worldbody>
|
||||
<body name="pelvis" pos="0 0 0.793">
|
||||
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="waist_yaw_link">
|
||||
<inertial pos="0.003964 0 0.018769" quat="-0.0178291 0.628464 0.0282471 0.777121" mass="0.244" diaginertia="0.000158561 0.000124229 9.67669e-05"/>
|
||||
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||
<body name="waist_roll_link" pos="-0.0039635 0 0.035">
|
||||
<inertial pos="0 -0.000236 0.010111" quat="0.99979 0.020492 0 0" mass="0.047" diaginertia="7.515e-06 6.40206e-06 3.98394e-06"/>
|
||||
<joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||
<body name="torso_link" pos="0 0 0.019">
|
||||
<inertial pos="0.00331658 0.000261533 0.179856" quat="0.999831 0.000376204 0.0179895 -0.00377704" mass="9.598" diaginertia="0.12407 0.111951 0.0325382"/>
|
||||
<joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||
<site name="imu" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.23778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||
<inertial pos="0.0885506 0.00212216 -0.000374562" quat="0.487149 0.493844 0.513241 0.505358" mass="0.457415" diaginertia="0.00105989 0.000895419 0.000323842"/>
|
||||
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
|
||||
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
|
||||
<body name="left_hand_zero_link" pos="0.0695 0.003 0">
|
||||
<inertial pos="-0.000354413 -0.0132989 0.000412362" quat="0.385163 0.591021 -0.567321 0.424842" mass="0.0803302" diaginertia="1.39245e-05 1.32309e-05 1.19138e-05"/>
|
||||
<joint name="left_hand_zero_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_zero_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_zero_link"/>
|
||||
<body name="left_hand_one_link" pos="0 -0.0246 0">
|
||||
<inertial pos="0.0036206 -0.040444 -0.000297711" quat="0.696371 0.699653 0.125539 -0.0989605" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
|
||||
<joint name="left_hand_one_joint" pos="0 0 0" axis="0 0 1" range="-0.724312 1.0472" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_one_link"/>
|
||||
<geom size="0.01 0.015 0.01" pos="-0.001 -0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_hand_two_link" pos="0.0055 -0.0528 0">
|
||||
<inertial pos="-0.00081406 -0.0345621 0.000129799" quat="0.701976 0.711984 0.0160342 0.00721768" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
|
||||
<joint name="left_hand_two_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_two_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_two_link"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_hand_three_link" pos="0.1415 0.0013 -0.0285">
|
||||
<inertial pos="0.040444 -0.0036206 0.000287711" quat="0.583499 0.422433 0.562384 0.40596" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
|
||||
<joint name="left_hand_three_joint" pos="0 0 0" axis="0 0 1" range="-1.8326 0.191986" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_three_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_three_link"/>
|
||||
<body name="left_hand_four_link" pos="0.0528 -0.0055 0">
|
||||
<inertial pos="0.0345621 0.00081406 -0.000129799" quat="0.514787 0.501475 0.491268 0.492111" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
|
||||
<joint name="left_hand_four_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_four_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_four_link"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_hand_five_link" pos="0.1415 0.0013 0.0285">
|
||||
<inertial pos="0.040444 -0.0036206 0.000287711" quat="0.583499 0.422433 0.562384 0.40596" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
|
||||
<joint name="left_hand_five_joint" pos="0 0 0" axis="0 0 1" range="-1.8326 0.191986" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_five_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_five_link"/>
|
||||
<body name="left_hand_six_link" pos="0.0528 -0.0055 0">
|
||||
<inertial pos="0.0345621 0.00081406 -0.000129799" quat="0.514787 0.501475 0.491268 0.492111" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
|
||||
<joint name="left_hand_six_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_six_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_six_link"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.23778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||
<inertial pos="0.0885506 -0.00212216 0.000573742" quat="0.507224 0.511377 0.494292 0.486717" mass="0.457415" diaginertia="0.0010598 0.000895373 0.0003238"/>
|
||||
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
|
||||
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
|
||||
<body name="right_hand_zero_link" pos="0.0695 -0.003 0">
|
||||
<inertial pos="-0.000354413 0.0132989 -0.000412362" quat="0.424842 0.567321 -0.591021 0.385163" mass="0.0803302" diaginertia="1.39245e-05 1.32309e-05 1.19138e-05"/>
|
||||
<joint name="right_hand_zero_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_zero_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_zero_link"/>
|
||||
<body name="right_hand_one_link" pos="0 0.0246 0">
|
||||
<inertial pos="0.0036206 0.040444 0.000297711" quat="0.696371 0.699653 -0.125539 0.0989605" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
|
||||
<joint name="right_hand_one_joint" pos="0 0 0" axis="0 0 1" range="-1.0472 0.724312" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_one_link"/>
|
||||
<geom size="0.01 0.015 0.01" pos="-0.001 0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_hand_two_link" pos="0.0055 0.0528 0">
|
||||
<inertial pos="-0.00081406 0.0345621 -0.000129799" quat="0.701976 0.711984 -0.0160342 -0.00721768" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
|
||||
<joint name="right_hand_two_joint" pos="0 0 0" axis="0 0 1" range="-2.0944 0" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_two_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_two_link"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_hand_three_link" pos="0.1415 -0.0013 0.0285">
|
||||
<inertial pos="0.040444 0.0036206 -0.000287711" quat="0.562384 0.40596 0.583499 0.422433" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
|
||||
<joint name="right_hand_three_joint" pos="0 0 0" axis="0 0 1" range="-0.191986 1.8326" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_three_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_three_link"/>
|
||||
<body name="right_hand_four_link" pos="0.0528 0.0055 0">
|
||||
<inertial pos="0.0345621 -0.00081406 0.000129799" quat="0.491268 0.492111 0.514787 0.501475" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
|
||||
<joint name="right_hand_four_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_four_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_four_link"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_hand_five_link" pos="0.1415 -0.0013 -0.0285">
|
||||
<inertial pos="0.040444 0.0036206 -0.000287711" quat="0.562384 0.40596 0.583499 0.422433" mass="0.0561963" diaginertia="1.23865e-05 1.2092e-05 5.00561e-06"/>
|
||||
<joint name="right_hand_five_joint" pos="0 0 0" axis="0 0 1" range="-0.191986 1.8326" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_five_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_five_link"/>
|
||||
<body name="right_hand_six_link" pos="0.0528 0.0055 0">
|
||||
<inertial pos="0.0345621 -0.00081406 0.000129799" quat="0.491268 0.492111 0.514787 0.501475" mass="0.0248731" diaginertia="8.60616e-06 7.69097e-06 1.98043e-06"/>
|
||||
<joint name="right_hand_six_joint" pos="0 0 0" axis="0 0 1" range="0 2.0944" actuatorfrcrange="-0.7 0.7"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_six_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_six_link"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||
<motor name="waist_roll_joint" joint="waist_roll_joint"/>
|
||||
<motor name="waist_pitch_joint" joint="waist_pitch_joint"/>
|
||||
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||
<motor name="left_hand_zero_joint" joint="left_hand_zero_joint"/>
|
||||
<motor name="left_hand_one_joint" joint="left_hand_one_joint"/>
|
||||
<motor name="left_hand_two_joint" joint="left_hand_two_joint"/>
|
||||
<motor name="left_hand_three_joint" joint="left_hand_three_joint"/>
|
||||
<motor name="left_hand_four_joint" joint="left_hand_four_joint"/>
|
||||
<motor name="left_hand_five_joint" joint="left_hand_five_joint"/>
|
||||
<motor name="left_hand_six_joint" joint="left_hand_six_joint"/>
|
||||
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||
<motor name="right_hand_zero_joint" joint="right_hand_zero_joint"/>
|
||||
<motor name="right_hand_one_joint" joint="right_hand_one_joint"/>
|
||||
<motor name="right_hand_two_joint" joint="right_hand_two_joint"/>
|
||||
<motor name="right_hand_three_joint" joint="right_hand_three_joint"/>
|
||||
<motor name="right_hand_four_joint" joint="right_hand_four_joint"/>
|
||||
<motor name="right_hand_five_joint" joint="right_hand_five_joint"/>
|
||||
<motor name="right_hand_six_joint" joint="right_hand_six_joint"/>
|
||||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
</sensor>
|
||||
|
||||
|
||||
<!-- setup scene -->
|
||||
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||
<visual>
|
||||
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||
<rgba haze="0.15 0.25 0.35 1"/>
|
||||
<global azimuth="-140" elevation="-20"/>
|
||||
</visual>
|
||||
<asset>
|
||||
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||
</worldbody>
|
||||
</mujoco>
|
|
@ -0,0 +1,627 @@
|
|||
<robot name="g1_dual_arm">
|
||||
<mujoco>
|
||||
<compiler meshdir="meshes" discardvisual="false"/>
|
||||
</mujoco>
|
||||
|
||||
<!-- [CAUTION] uncomment when convert to mujoco -->
|
||||
<!-- <link name="world"></link>
|
||||
<joint name="floating_base_joint" type="floating">
|
||||
<parent link="world"/>
|
||||
<child link="waist_yaw_link"/>
|
||||
</joint> -->
|
||||
|
||||
<!-- Torso -->
|
||||
<link name="waist_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="0.003964 0 0.018769" rpy="0 0 0"/>
|
||||
<mass value="0.244"/>
|
||||
<inertia ixx="9.9587E-05" ixy="-1.833E-06" ixz="-1.2617E-05" iyy="0.00012411" iyz="-1.18E-07" izz="0.00015586"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/waist_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="waist_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="0 -0.000236 0.010111" rpy="0 0 0"/>
|
||||
<mass value="0.047"/>
|
||||
<inertia ixx="7.515E-06" ixy="0" ixz="0" iyy="6.398E-06" iyz="9.9E-08" izz="3.988E-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/waist_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="waist_roll_joint" type="fixed">
|
||||
<origin xyz="-0.0039635 0 0.035" rpy="0 0 0"/>
|
||||
<parent link="waist_yaw_link"/>
|
||||
<child link="waist_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-0.52" upper="0.52" effort="50" velocity="37"/>
|
||||
</joint>
|
||||
<link name="torso_link">
|
||||
<inertial>
|
||||
<origin xyz="0.002601 0.000257 0.153719" rpy="0 0 0"/>
|
||||
<mass value="8.562"/>
|
||||
<inertia ixx="0.065674966" ixy="-8.597E-05" ixz="-0.001737252" iyy="0.053535188" iyz="8.6899E-05" izz="0.030808125"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/torso_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/torso_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="waist_pitch_joint" type="fixed">
|
||||
<origin xyz="0 0 0.019" rpy="0 0 0"/>
|
||||
<parent link="waist_roll_link"/>
|
||||
<child link="torso_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-0.52" upper="0.52" effort="50" velocity="37"/>
|
||||
</joint>
|
||||
|
||||
<!-- LOGO -->
|
||||
<joint name="logo_joint" type="fixed">
|
||||
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="logo_link"/>
|
||||
</joint>
|
||||
<link name="logo_link">
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="0.001"/>
|
||||
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/logo_link.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/logo_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!-- Head -->
|
||||
<link name="head_link">
|
||||
<inertial>
|
||||
<origin xyz="0.005267 0.000299 0.449869" rpy="0 0 0"/>
|
||||
<mass value="1.036"/>
|
||||
<inertia ixx="0.004085051" ixy="-2.543E-06" ixz="-6.9455E-05" iyy="0.004185212" iyz="-3.726E-06" izz="0.001807911"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/head_link.STL"/>
|
||||
</geometry>
|
||||
<material name="dark">
|
||||
<color rgba="0.2 0.2 0.2 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/head_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="head_joint" type="fixed">
|
||||
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="head_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- Waist Support -->
|
||||
<link name="waist_support_link">
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="0.001"/>
|
||||
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/waist_support_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/waist_support_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="waist_support_joint" type="fixed">
|
||||
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="waist_support_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<origin xyz="-0.03959 -0.00224 0.13792" rpy="0 0 0"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="imu_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- Arm -->
|
||||
<link name="left_shoulder_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="0 0.035892 -0.011628" rpy="0 0 0"/>
|
||||
<mass value="0.718"/>
|
||||
<inertia ixx="0.0004291" ixy="-9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="2.26E-05" izz="0.000423"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_shoulder_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_shoulder_pitch_joint" type="revolute">
|
||||
<origin xyz="0.0039563 0.10022 0.23778" rpy="0.27931 5.4949E-05 -0.00019159"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="left_shoulder_pitch_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="left_shoulder_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.000227 0.00727 -0.063243" rpy="0 0 0"/>
|
||||
<mass value="0.643"/>
|
||||
<inertia ixx="0.0006177" ixy="-1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="-5.3E-06" izz="0.0003894"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_shoulder_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.004 0.006 -0.053" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_shoulder_roll_joint" type="revolute">
|
||||
<origin xyz="0 0.038 -0.013831" rpy="-0.27925 0 0"/>
|
||||
<parent link="left_shoulder_pitch_link"/>
|
||||
<child link="left_shoulder_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-1.5882" upper="2.2515" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="left_shoulder_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="0.010773 -0.002949 -0.072009" rpy="0 0 0"/>
|
||||
<mass value="0.734"/>
|
||||
<inertia ixx="0.0009988" ixy="7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="-2.86E-05" izz="0.0004354"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_shoulder_yaw_joint" type="revolute">
|
||||
<origin xyz="0 0.00624 -0.1032" rpy="0 0 0"/>
|
||||
<parent link="left_shoulder_roll_link"/>
|
||||
<child link="left_shoulder_yaw_link"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="left_elbow_link">
|
||||
<inertial>
|
||||
<origin xyz="0.064956 0.004454 -0.010062" rpy="0 0 0"/>
|
||||
<mass value="0.6"/>
|
||||
<inertia ixx="0.0002891" ixy="6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="-5.6E-06" izz="0.0004197"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_elbow_joint" type="revolute">
|
||||
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||
<parent link="left_shoulder_yaw_link"/>
|
||||
<child link="left_elbow_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<joint name="left_wrist_roll_joint" type="revolute">
|
||||
<origin xyz="0.100 0.00188791 -0.010" rpy="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="left_elbow_link"/>
|
||||
<child link="left_wrist_roll_link"/>
|
||||
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||
</joint>
|
||||
<link name="left_wrist_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="0.01713944778 0.00053759094 0.00000048864" rpy="0 0 0"/>
|
||||
<mass value="0.08544498"/>
|
||||
<inertia ixx="0.00004821544023" ixy="-0.00000424511021" ixz="0.00000000510599" iyy="0.00003722899093" iyz="-0.00000000123525" izz="0.00005482106541"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_wrist_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_wrist_roll_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_wrist_pitch_joint" type="revolute">
|
||||
<origin xyz="0.038 0 0" rpy="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="left_wrist_roll_link"/>
|
||||
<child link="left_wrist_pitch_link"/>
|
||||
<limit effort="5" velocity="22" lower="-1.614429558" upper="1.614429558"/>
|
||||
</joint>
|
||||
<link name="left_wrist_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="0.02299989837 -0.00111685314 -0.00111658096" rpy="0 0 0"/>
|
||||
<mass value="0.48404956"/>
|
||||
<inertia ixx="0.00016579646273" ixy="-0.00001231206746" ixz="0.00001231699194" iyy="0.00042954057410" iyz="0.00000081417712" izz="0.00042953697654"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_wrist_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_wrist_pitch_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_wrist_yaw_joint" type="revolute">
|
||||
<origin xyz="0.046 0 0" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<parent link="left_wrist_pitch_link"/>
|
||||
<child link="left_wrist_yaw_link"/>
|
||||
<limit effort="5" velocity="22" lower="-1.614429558" upper="1.614429558"/>
|
||||
</joint>
|
||||
<link name="left_wrist_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="0.02200381568 0.00049485096 0.00053861123" rpy="0 0 0"/>
|
||||
<mass value="0.08457647"/>
|
||||
<inertia ixx="0.00004929128828" ixy="-0.00000045735494" ixz="0.00000445867591" iyy="0.00005973338134" iyz="0.00000043217198" izz="0.00003928083826"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_wrist_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_wrist_yaw_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="left_hand_palm_joint" type="fixed">
|
||||
<origin xyz="0.0415 0.003 0" rpy="0 0 0"/>
|
||||
<parent link="left_wrist_yaw_link"/>
|
||||
<child link="left_rubber_hand"/>
|
||||
</joint>
|
||||
<link name="left_rubber_hand">
|
||||
<inertial>
|
||||
<origin xyz="0.05361310808 -0.00295905240 0.00215413091" rpy="0 0 0"/>
|
||||
<mass value="0.170"/>
|
||||
<inertia ixx="0.00010099485234748" ixy="0.00003618590790516" ixz="-0.00000074301518642" iyy="0.00028135871571621" iyz="0.00000330189743286" izz="0.00021894770413514"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/left_rubber_hand.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="right_shoulder_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="0 -0.035892 -0.011628" rpy="0 0 0"/>
|
||||
<mass value="0.718"/>
|
||||
<inertia ixx="0.0004291" ixy="9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="-2.26E-05" izz="0.000423"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_shoulder_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 -0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_shoulder_pitch_joint" type="revolute">
|
||||
<origin xyz="0.0039563 -0.10021 0.23778" rpy="-0.27931 5.4949E-05 0.00019159"/>
|
||||
<parent link="torso_link"/>
|
||||
<child link="right_shoulder_pitch_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="right_shoulder_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="-0.000227 -0.00727 -0.063243" rpy="0 0 0"/>
|
||||
<mass value="0.643"/>
|
||||
<inertia ixx="0.0006177" ixy="1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="5.3E-06" izz="0.0003894"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_shoulder_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="-0.004 -0.006 -0.053" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_shoulder_roll_joint" type="revolute">
|
||||
<origin xyz="0 -0.038 -0.013831" rpy="0.27925 0 0"/>
|
||||
<parent link="right_shoulder_pitch_link"/>
|
||||
<child link="right_shoulder_roll_link"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit lower="-2.2515" upper="1.5882" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="right_shoulder_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="0.010773 0.002949 -0.072009" rpy="0 0 0"/>
|
||||
<mass value="0.734"/>
|
||||
<inertia ixx="0.0009988" ixy="-7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="2.86E-05" izz="0.0004354"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_shoulder_yaw_joint" type="revolute">
|
||||
<origin xyz="0 -0.00624 -0.1032" rpy="0 0 0"/>
|
||||
<parent link="right_shoulder_roll_link"/>
|
||||
<child link="right_shoulder_yaw_link"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<link name="right_elbow_link">
|
||||
<inertial>
|
||||
<origin xyz="0.064956 -0.004454 -0.010062" rpy="0 0 0"/>
|
||||
<mass value="0.6"/>
|
||||
<inertia ixx="0.0002891" ixy="-6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="5.6E-06" izz="0.0004197"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_elbow_joint" type="revolute">
|
||||
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||
<parent link="right_shoulder_yaw_link"/>
|
||||
<child link="right_elbow_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||
</joint>
|
||||
<joint name="right_wrist_roll_joint" type="revolute">
|
||||
<origin xyz="0.100 -0.00188791 -0.010" rpy="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="right_elbow_link"/>
|
||||
<child link="right_wrist_roll_link"/>
|
||||
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||
</joint>
|
||||
<link name="right_wrist_roll_link">
|
||||
<inertial>
|
||||
<origin xyz="0.01713944778 -0.00053759094 0.00000048864" rpy="0 0 0"/>
|
||||
<mass value="0.08544498"/>
|
||||
<inertia ixx="0.00004821544023" ixy="0.00000424511021" ixz="0.00000000510599" iyy="0.00003722899093" iyz="0.00000000123525" izz="0.00005482106541"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_wrist_roll_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_wrist_roll_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_wrist_pitch_joint" type="revolute">
|
||||
<origin xyz="0.038 0 0" rpy="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="right_wrist_roll_link"/>
|
||||
<child link="right_wrist_pitch_link"/>
|
||||
<limit effort="5" velocity="22" lower="-1.614429558" upper="1.614429558"/>
|
||||
</joint>
|
||||
<link name="right_wrist_pitch_link">
|
||||
<inertial>
|
||||
<origin xyz="0.02299989837 0.00111685314 -0.00111658096" rpy="0 0 0"/>
|
||||
<mass value="0.48404956"/>
|
||||
<inertia ixx="0.00016579646273" ixy="0.00001231206746" ixz="0.00001231699194" iyy="0.00042954057410" iyz="-0.00000081417712" izz="0.00042953697654"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_wrist_pitch_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_wrist_pitch_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_wrist_yaw_joint" type="revolute">
|
||||
<origin xyz="0.046 0 0" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<parent link="right_wrist_pitch_link"/>
|
||||
<child link="right_wrist_yaw_link"/>
|
||||
<limit effort="5" velocity="22" lower="-1.614429558" upper="1.614429558"/>
|
||||
</joint>
|
||||
<link name="right_wrist_yaw_link">
|
||||
<inertial>
|
||||
<origin xyz="0.02200381568 -0.00049485096 0.00053861123" rpy="0 0 0"/>
|
||||
<mass value="0.08457647"/>
|
||||
<inertia ixx="0.00004929128828" ixy="0.00000045735494" ixz="0.00000445867591" iyy="0.00005973338134" iyz="-0.00000043217198" izz="0.00003928083826"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_wrist_yaw_link.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_wrist_yaw_link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="right_hand_palm_joint" type="fixed">
|
||||
<origin xyz="0.0415 -0.003 0" rpy="0 0 0"/>
|
||||
<parent link="right_wrist_yaw_link"/>
|
||||
<child link="right_rubber_hand"/>
|
||||
</joint>
|
||||
<link name="right_rubber_hand">
|
||||
<inertial>
|
||||
<origin xyz="0.05361310808 0.00295905240 0.00215413091" rpy="0 0 0"/>
|
||||
<mass value="0.170"/>
|
||||
<inertia ixx="0.00010099485234748" ixy="-0.00003618590790516" ixz="-0.00000074301518642" iyy="0.00028135871571621" iyz="-0.00000330189743286" izz="0.00021894770413514"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/right_rubber_hand.STL"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="0.7 0.7 0.7 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
|
@ -0,0 +1,162 @@
|
|||
<mujoco model="g1_dual_arm">
|
||||
<compiler angle="radian" meshdir="meshes"/>
|
||||
|
||||
<asset>
|
||||
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||
<mesh name="waist_roll_link" file="waist_roll_link.STL"/>
|
||||
<mesh name="torso_link" file="torso_link.STL"/>
|
||||
<mesh name="logo_link" file="logo_link.STL"/>
|
||||
<mesh name="head_link" file="head_link.STL"/>
|
||||
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||
<mesh name="left_rubber_hand" file="left_rubber_hand.STL"/>
|
||||
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||
<mesh name="right_rubber_hand" file="right_rubber_hand.STL"/>
|
||||
</asset>
|
||||
|
||||
<worldbody>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||
<geom pos="-0.0039635 0 0.035" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||
<geom pos="-0.0039635 0 0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom pos="-0.0039635 0 0.054" type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||
<body name="left_shoulder_pitch_link" pos="-7.2e-06 0.10022 0.29178" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||
<inertial pos="0.0708244 0.000191745 0.00161742" quat="0.510571 0.526295 0.468078 0.493188" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_rubber_hand"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_shoulder_pitch_link" pos="-7.2e-06 -0.10021 0.29178" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||
<inertial pos="0.0708244 -0.000191745 0.00161742" quat="0.493188 0.468078 0.526295 0.510571" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_rubber_hand"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||
</actuator>
|
||||
|
||||
|
||||
<!-- setup scene -->
|
||||
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||
<visual>
|
||||
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||
<rgba haze="0.15 0.25 0.35 1"/>
|
||||
<global azimuth="-140" elevation="-20"/>
|
||||
</visual>
|
||||
<asset>
|
||||
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||
</worldbody>
|
||||
</mujoco>
|
|
@ -0,0 +1,115 @@
|
|||
# 电机顺序
|
||||
|
||||
## G1 全身关节电机顺序
|
||||
|
||||
`unitree_hg::msg::dds_::LowCmd_.motor_cmd` 与 `unitree_hg::msg::dds_::LowState_.motor_state` 包含 G1 全身电机(不含手)的信息,其电机顺序如下:
|
||||
|
||||
### 23DOF 版本
|
||||
|
||||
| Joint Index in IDL | Joint Name (LowCmd_.mode or LowState_.mode == 0) | Joint Name (LowCmd_.mode or LowState_.mode == 1) |
|
||||
| ------------------ | ------------------------------------------------ | ------------------------------------------------ |
|
||||
| 0 | L_LEG_HIP_PITCH | L_LEG_HIP_PITCH |
|
||||
| 1 | L_LEG_HIP_ROLL | L_LEG_HIP_ROLL |
|
||||
| 2 | L_LEG_HIP_YAW | L_LEG_HIP_YAW |
|
||||
| 3 | L_LEG_KNEE | L_LEG_KNEE |
|
||||
| 4 | **L_LEG_ANKLE_PITCH** | **L_LEG_ANKLE_B** |
|
||||
| 5 | **L_LEG_ANKLE_ROLL** | **L_LEG_ANKLE_A** |
|
||||
| 6 | R_LEG_HIP_PITCH | R_LEG_HIP_PITCH |
|
||||
| 7 | R_LEG_HIP_ROLL | R_LEG_HIP_ROLL |
|
||||
| 8 | R_LEG_HIP_YAW | R_LEG_HIP_YAW |
|
||||
| 9 | R_LEG_KNEE | R_LEG_KNEE |
|
||||
| 10 | **R_LEG_ANKLE_PITCH** | **R_LEG_ANKLE_B** |
|
||||
| 11 | **R_LEG_ANKLE_ROLL** | **R_LEG_ANKLE_A** |
|
||||
| 12 | TORSO | TORSO |
|
||||
| 13 | L_SHOULDER_PITCH | L_SHOULDER_PITCH |
|
||||
| 14 | L_SHOULDER_ROLL | L_SHOULDER_ROLL |
|
||||
| 15 | L_SHOULDER_YAW | L_SHOULDER_YAW |
|
||||
| 16 | L_ELBOW_PITCH | L_ELBOW_PITCH |
|
||||
| 17 | L_ELBOW_ROLL | L_ELBOW_ROLL |
|
||||
| 18 | R_SHOULDER_PITCH | R_SHOULDER_PITCH |
|
||||
| 19 | R_SHOULDER_ROLL | R_SHOULDER_ROLL |
|
||||
| 20 | R_SHOULDER_YAW | R_SHOULDER_YAW |
|
||||
| 21 | R_ELBOW_PITCH | R_ELBOW_PITCH |
|
||||
| 22 | R_ELBOW_ROLL | R_ELBOW_ROLL |
|
||||
|
||||
### 29DOF 版本
|
||||
|
||||
| Joint Index in IDL | Joint Name (LowCmd_.mode or LowState_.mode == 0) | Joint Name (LowCmd_.mode or LowState_.mode == 1) |
|
||||
| ------------------ | ------------------------------------------------ | ------------------------------------------------ |
|
||||
| 0 | L_LEG_HIP_PITCH | L_LEG_HIP_PITCH |
|
||||
| 1 | L_LEG_HIP_ROLL | L_LEG_HIP_ROLL |
|
||||
| 2 | L_LEG_HIP_YAW | L_LEG_HIP_YAW |
|
||||
| 3 | L_LEG_KNEE | L_LEG_KNEE |
|
||||
| 4 | **L_LEG_ANKLE_PITCH** | **L_LEG_ANKLE_B** |
|
||||
| 5 | **L_LEG_ANKLE_ROLL** | **L_LEG_ANKLE_A** |
|
||||
| 6 | R_LEG_HIP_PITCH | R_LEG_HIP_PITCH |
|
||||
| 7 | R_LEG_HIP_ROLL | R_LEG_HIP_ROLL |
|
||||
| 8 | R_LEG_HIP_YAW | R_LEG_HIP_YAW |
|
||||
| 9 | R_LEG_KNEE | R_LEG_KNEE |
|
||||
| 10 | **R_LEG_ANKLE_PITCH** | **R_LEG_ANKLE_B** |
|
||||
| 11 | **R_LEG_ANKLE_ROLL** | **R_LEG_ANKLE_A** |
|
||||
| 12 | WAIST_YAW | WAIST_YAW |
|
||||
| 13 | **WAIST_ROLL** | **WAIST_A** |
|
||||
| 14 | **WAIST_PITCH** | **WAIST_B** |
|
||||
| 15 | L_SHOULDER_PITCH | L_SHOULDER_PITCH |
|
||||
| 16 | L_SHOULDER_ROLL | L_SHOULDER_ROLL |
|
||||
| 17 | L_SHOULDER_YAW | L_SHOULDER_YAW |
|
||||
| 18 | L_ELBOW | L_ELBOW |
|
||||
| 19 | L_WRIST_ROLL | L_WRIST_ROLL |
|
||||
| 20 | L_WRIST_PITCH | L_WRIST_PITCH |
|
||||
| 21 | L_WRIST_YAW | L_WRIST_YAW |
|
||||
| 22 | R_SHOULDER_PITCH | R_SHOULDER_PITCH |
|
||||
| 23 | R_SHOULDER_ROLL | R_SHOULDER_ROLL |
|
||||
| 24 | R_SHOULDER_YAW | R_SHOULDER_YAW |
|
||||
| 25 | R_ELBOW | R_ELBOW |
|
||||
| 26 | R_WRIST_ROLL | R_WRIST_ROLL |
|
||||
| 27 | R_WRIST_PITCH | R_WRIST_PITCH |
|
||||
| 28 | R_WRIST_YAW | R_WRIST_YAW |
|
||||
|
||||
### 14DOF 双臂版本
|
||||
|
||||
| Joint Index in IDL | Joint Name |
|
||||
| ------------------ | ---------------- |
|
||||
| 0 | (empty) |
|
||||
| 1 | (empty) |
|
||||
| 2 | (empty) |
|
||||
| 3 | (empty) |
|
||||
| 4 | (empty) |
|
||||
| 5 | (empty) |
|
||||
| 6 | (empty) |
|
||||
| 7 | (empty) |
|
||||
| 8 | (empty) |
|
||||
| 9 | (empty) |
|
||||
| 10 | (empty) |
|
||||
| 11 | (empty) |
|
||||
| 12 | (empty) |
|
||||
| 13 | (empty) |
|
||||
| 14 | (empty) |
|
||||
| 15 | L_SHOULDER_PITCH |
|
||||
| 16 | L_SHOULDER_ROLL |
|
||||
| 17 | L_SHOULDER_YAW |
|
||||
| 18 | L_ELBOW |
|
||||
| 19 | L_WRIST_ROLL |
|
||||
| 20 | L_WRIST_PITCH |
|
||||
| 21 | L_WRIST_YAW |
|
||||
| 22 | R_SHOULDER_PITCH |
|
||||
| 23 | R_SHOULDER_ROLL |
|
||||
| 24 | R_SHOULDER_YAW |
|
||||
| 25 | R_ELBOW |
|
||||
| 26 | R_WRIST_ROLL |
|
||||
| 27 | R_WRIST_PITCH |
|
||||
| 28 | R_WRIST_YAW |
|
||||
|
||||
## Dex3-1 关节电机顺序
|
||||
|
||||
`unitree_hg::msg::dds_::HandCmd_.motor_cmd` 与 `unitree_hg::msg::dds_::HandState_.motor_state` 包含所有的灵巧手电机的信息,其电机顺序如下:
|
||||
|
||||
| Hand Joint Index in IDL | Hand Joint Name |
|
||||
| ----------------------- | --------------- |
|
||||
| 0 | thumb_0 |
|
||||
| 1 | thumb_1 |
|
||||
| 2 | thumb_2 |
|
||||
| 3 | index_0 |
|
||||
| 4 | index_1 |
|
||||
| 5 | middle_0 |
|
||||
| 6 | middle_1 |
|
Binary file not shown.
After Width: | Height: | Size: 912 KiB |
Binary file not shown.
After Width: | Height: | Size: 920 KiB |
Binary file not shown.
After Width: | Height: | Size: 922 KiB |
Binary file not shown.
After Width: | Height: | Size: 827 KiB |
|
@ -1,239 +0,0 @@
|
|||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 719
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Preferences:
|
||||
PromptSaveOnExit: true
|
||||
Toolbars:
|
||||
toolButtonStyle: 2
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
pelvis:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
hip_rotation_link_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
hip_abduction_link_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
hip_flexion_link_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
knee_link_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
ankle_link_left:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
hip_rotation_link_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
hip_abduction_link_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
hip_flexion_link_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
knee_link_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
ankle_link_right:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
Robot Description: robot_description
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz/TF
|
||||
Enabled: true
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
pelvis:
|
||||
Value: true
|
||||
hip_rotation_link_left:
|
||||
Value: true
|
||||
hip_abduction_link_left:
|
||||
Value: true
|
||||
hip_flexion_link_left:
|
||||
Value: true
|
||||
knee_link_left:
|
||||
Value: true
|
||||
ankle_link_left:
|
||||
Value: true
|
||||
hip_rotation_link_right:
|
||||
Value: true
|
||||
hip_abduction_link_right:
|
||||
Value: true
|
||||
hip_flexion_link_right:
|
||||
Value: true
|
||||
knee_link_right:
|
||||
Value: true
|
||||
ankle_link_right:
|
||||
Value: true
|
||||
Marker Alpha: 1
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
pelvis:
|
||||
hip_rotation_link_left:
|
||||
hip_abduction_link_left:
|
||||
hip_flexion_link_left:
|
||||
knee_link_left:
|
||||
ankle_link_left:
|
||||
{}
|
||||
hip_rotation_link_right:
|
||||
hip_abduction_link_right:
|
||||
hip_flexion_link_right:
|
||||
knee_link_right:
|
||||
ankle_link_right:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Default Light: true
|
||||
Fixed Frame: pelvis
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Theta std deviation: 0.2617993950843811
|
||||
Topic: /initialpose
|
||||
X std deviation: 0.5
|
||||
Y std deviation: 0.5
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 1.6701574325561523
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Field of View: 0.7853981852531433
|
||||
Focal Point:
|
||||
X: 0.11145864427089691
|
||||
Y: 0.10033124685287476
|
||||
Z: -0.35909000039100647
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.5303982496261597
|
||||
Target Frame: <Fixed Frame>
|
||||
Yaw: 0.8653979301452637
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 1016
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001560000035afc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000035a000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000035afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d0000035a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000074c0000003efc0100000002fb0000000800540069006d006501000000000000074c000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000004db0000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1868
|
||||
X: 52
|
||||
Y: 27
|
|
@ -1,7 +0,0 @@
|
|||
<launch>
|
||||
<arg name="model"/>
|
||||
<param name="robot_description" textfile="$(find g1_description)/g1.urdf"/>
|
||||
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui"/>
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
||||
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find g1_description)/launch/check_joint.rviz"/>
|
||||
</launch>
|
|
@ -1,82 +0,0 @@
|
|||
<launch>
|
||||
<arg name="wname" default="earth"/>
|
||||
<arg name="rname" default="g1"/>
|
||||
<arg name="robot_path" value="(find $(arg rname)_description)"/>
|
||||
<arg name="dollar" value="$"/>
|
||||
|
||||
<arg name="paused" default="true"/>
|
||||
<arg name="use_sim_time" default="true"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="debug" default="false"/>
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<arg name="user_debug" default="true"/>
|
||||
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="world_name" value="$(find unitree_gazebo)/worlds/$(arg wname).world"/>
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
</include>
|
||||
|
||||
<!-- Load the URDF into the ROS Parameter Server -->
|
||||
<param name="robot_description"
|
||||
command="$(find xacro)/xacro --inorder '$(arg dollar)$(arg robot_path)/xacro/robot.xacro'
|
||||
DEBUG:=$(arg user_debug)"/>
|
||||
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
|
||||
<!-- Set trunk and joint positions at startup -->
|
||||
<node pkg="gazebo_ros" type="spawn_model" name="urdf_spawner" respawn="false" output="screen"
|
||||
args="-urdf -z 0.6 -model $(arg rname)_gazebo -param robot_description -unpause"/>
|
||||
|
||||
<!-- Load joint controller configurations from YAML file to parameter server -->
|
||||
<rosparam file="$(arg dollar)$(arg robot_path)/config/robot_control.yaml" command="load"/>
|
||||
|
||||
<!-- load the controllers -->
|
||||
<node pkg="controller_manager" type="spawner" name="controller_spawner" respawn="false"
|
||||
output="screen" ns="/$(arg rname)_gazebo" args="joint_state_controller
|
||||
|
||||
torso_controller
|
||||
|
||||
left_hip_pitch_controller
|
||||
left_hip_roll_controller
|
||||
left_hip_yaw_controller
|
||||
left_knee_controller
|
||||
left_ankle_pitch_controller
|
||||
left_ankle_roll_controller
|
||||
|
||||
right_hip_pitch_controller
|
||||
right_hip_roll_controller
|
||||
right_hip_yaw_controller
|
||||
right_knee_controller
|
||||
right_ankle_pitch_controller
|
||||
right_ankle_roll_controller
|
||||
|
||||
left_shoulder_pitch_controller
|
||||
left_shoulder_roll_controller
|
||||
left_shoulder_yaw_controller
|
||||
left_elbow_pitch_controller
|
||||
left_elbow_roll_controller
|
||||
|
||||
right_shoulder_pitch_controller
|
||||
right_shoulder_roll_controller
|
||||
right_shoulder_yaw_controller
|
||||
right_elbow_pitch_controller
|
||||
right_elbow_roll_controller
|
||||
"/>
|
||||
|
||||
<!-- convert joint states to TF transforms for rviz, etc -->
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"
|
||||
respawn="false" output="screen">
|
||||
<remap from="/joint_states" to="/$(arg rname)_gazebo/joint_states"/>
|
||||
</node>
|
||||
|
||||
<!-- <node pkg="unitree_gazebo" type="servo" name="servo" required="true" output="screen"/> -->
|
||||
|
||||
<!-- load the parameter unitree_controller -->
|
||||
<include file="$(find unitree_controller)/launch/set_ctrl.launch">
|
||||
<arg name="rname" value="$(arg rname)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue