add g1_description
This commit is contained in:
parent
f99ca83976
commit
727e8f8414
|
@ -0,0 +1,13 @@
|
|||
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)
|
|
@ -0,0 +1,67 @@
|
|||
# Unitree G1 Description (URDF & MJCF)
|
||||
|
||||
## Overview
|
||||
|
||||
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"/>
|
||||
</p>
|
||||
|
||||
Unitree G1 have 37 DOFs:
|
||||
|
||||
```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/
|
||||
```
|
||||
|
||||
## Visulization with [MuJoCo](https://github.com/google-deepmind/mujoco)
|
||||
|
||||
1. Open MuJoCo Viewer
|
||||
|
||||
```bash
|
||||
pip install mujoco
|
||||
|
||||
python -m mujoco.viewer
|
||||
```
|
||||
|
||||
2. Drag and drop the MJCF/URDF model file (`scene.xml`/`g1.urdf`) to the MuJoCo Viewer.
|
Binary file not shown.
After Width: | Height: | Size: 403 KiB |
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,334 @@
|
|||
<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,239 @@
|
|||
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
|
|
@ -0,0 +1,7 @@
|
|||
<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>
|
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.
|
@ -0,0 +1,13 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>g1_description</name>
|
||||
<version>1.0.0</version>
|
||||
<description>The Unitree G1 Description Package</description>
|
||||
<maintainer email="TODO@email.com"/>
|
||||
<license>TODO</license>
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<depend>roslaunch</depend>
|
||||
<depend>robot_state_publisher</depend>
|
||||
<depend>rviz</depend>
|
||||
<depend>joint_state_publisher_gui</depend>
|
||||
</package>
|
|
@ -0,0 +1,22 @@
|
|||
<mujoco model="g1 scene">
|
||||
<include file="g1.xml"/>
|
||||
|
||||
<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>
|
Loading…
Reference in New Issue