add new xml and python scripts

This commit is contained in:
Hongbo Zhu 2021-11-01 16:51:26 +08:00
parent cffce6f250
commit de538638d0
22 changed files with 2066 additions and 1 deletions

3
MUJOCO_LOG.TXT Normal file
View File

@ -0,0 +1,3 @@
Mon Nov 1 15:55:46 2021
ERROR: Could not open activation key file mjkey.txt

View File

@ -1 +1,4 @@
# unitree_mujoco
# Introduction
[MuJoCo](https://mujoco.org/) stands for Multi-Joint dynamics with Contact. It is a physics engine for simulation and has been open source. To relise more details, see these repositories: [MuJoCo](https://github.com/deepmind/mujoco) and [MuJuCo-py](https://github.com/openai/mujoco-py).
In this repo, some mujoco example scripts and the xml files of different Unitree robots are provided.

BIN
data/a1/meshes/calf.stl Normal file

Binary file not shown.

BIN
data/a1/meshes/hip.stl Normal file

Binary file not shown.

BIN
data/a1/meshes/thigh.stl Normal file

Binary file not shown.

Binary file not shown.

BIN
data/a1/meshes/trunk.stl Normal file

Binary file not shown.

719
data/a1/urdf/a1.urdf Normal file
View File

@ -0,0 +1,719 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="a1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<mujoco>
<compiler
meshdir="../meshes/"
balanceinertia="true"
discardvisual="false" />
<option gravity='0 0 -9.8'/>
</mujoco>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="silver">
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<!-- <xacro:include filename="$(find aliengo_gazebo)/launch/gazebo.xacro"/> -->
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
<!-- <xacro:if value="$(arg DEBUG)">
<link name="world"/>
<joint name="base_static_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base"/>
</joint>
</xacro:if> -->
<link name="world"/>
<joint name="floating_base" type="floating">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="trunk"/>
</joint>
<link name="trunk">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/trunk.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.267 0.194 0.114"/>
</geometry>
</collision>
<!-- <collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/trunk.stl" scale="1 1 1"/>
</geometry>
</collision> -->
<inertial>
<origin rpy="0 0 0" xyz="0.012731 0.002186 0.000515"/>
<mass value="4.713"/>
<inertia ixx="0.01683993" ixy="8.3902e-05" ixz="0.000597679" iyy="0.056579028" iyz="2.5134e-05" izz="0.064713601"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="trunk"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
</link>
<joint name="FR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.183 -0.047 0"/>
<parent link="trunk"/>
<child link="FR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
</joint>
<link name="FR_hip">
<visual>
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 -0.055 0"/>
<geometry>
<cylinder length="0.08" radius="0.04"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003311 -0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<!-- <joint name="${name}_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_shoulder"/>
</joint> -->
<!-- this link is only for collision -->
<!-- <link name="${name}_thigh_shoulder">
<collision>
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
</geometry>
</collision>
</link> -->
<joint name="FR_thigh_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 -0.08505 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
</joint>
<link name="FR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FR_thigh"/>
<child link="FR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
</joint>
<link name="FR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="FR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FR_calf"/>
<child link="FR_foot"/>
</joint>
<link name="FR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
</inertial>
</link>
<transmission name="FR_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="FL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.183 0.047 0"/>
<parent link="trunk"/>
<child link="FL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
</joint>
<link name="FL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0.055 0"/>
<geometry>
<cylinder length="0.08" radius="0.04"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003311 0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<!-- <joint name="${name}_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_shoulder"/>
</joint> -->
<!-- this link is only for collision -->
<!-- <link name="${name}_thigh_shoulder">
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
</geometry>
</collision>
</link> -->
<joint name="FL_thigh_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0.08505 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
</joint>
<link name="FL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FL_thigh"/>
<child link="FL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
</joint>
<link name="FL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="FL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FL_calf"/>
<child link="FL_foot"/>
</joint>
<link name="FL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
</inertial>
</link>
<transmission name="FL_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="RR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.183 -0.047 0"/>
<parent link="trunk"/>
<child link="RR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
</joint>
<link name="RR_hip">
<visual>
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 -0.055 0"/>
<geometry>
<cylinder length="0.08" radius="0.04"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.003311 -0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<!-- <joint name="${name}_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_shoulder"/>
</joint> -->
<!-- this link is only for collision -->
<!-- <link name="${name}_thigh_shoulder">
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
</geometry>
</collision>
</link> -->
<joint name="RR_thigh_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 -0.08505 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
</joint>
<link name="RR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="RR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="RR_thigh"/>
<child link="RR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
</joint>
<link name="RR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="RR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="RR_calf"/>
<child link="RR_foot"/>
</joint>
<link name="RR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
</inertial>
</link>
<transmission name="RR_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RR_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RR_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="RL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.183 0.047 0"/>
<parent link="trunk"/>
<child link="RL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-0.802851455917" upper="0.802851455917" velocity="52.4"/>
</joint>
<link name="RL_hip">
<visual>
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0.055 0"/>
<geometry>
<cylinder length="0.08" radius="0.04"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.003311 0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<!-- <joint name="${name}_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_shoulder"/>
</joint> -->
<!-- this link is only for collision -->
<!-- <link name="${name}_thigh_shoulder">
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
</geometry>
</collision>
</link> -->
<joint name="RL_thigh_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0.08505 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-1.0471975512" upper="4.18879020479" velocity="28.6"/>
</joint>
<link name="RL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="RL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="RL_thigh"/>
<child link="RL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.69653369433" upper="-0.916297857297" velocity="28.6"/>
</joint>
<link name="RL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="RL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="RL_calf"/>
<child link="RL_foot"/>
</joint>
<link name="RL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
</inertial>
</link>
<transmission name="RL_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RL_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RL_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>

139
data/a1/urdf/a1.xml Normal file
View File

@ -0,0 +1,139 @@
<mujoco model="a1_description">
<compiler angle="radian" meshdir="../meshes/" />
<option gravity="0 0 -9.8" />
<size njmax="500" nconmax="100" />
<asset>
<mesh name="trunk" file="trunk.stl" />
<mesh name="hip" file="hip.stl" />
<mesh name="thigh_mirror" file="thigh_mirror.stl" />
<mesh name="calf" file="calf.stl" />
<mesh name="thigh" file="thigh.stl" />
</asset>
<worldbody>
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
<geom type="plane" pos="0 0 -0.45" size="10 10 0.1" rgba=".9 0 0 1"/>
<body name="trunk" pos="0 0 0">
<inertial pos="0.0127283 0.00218554 0.000514891" quat="0.00186575 0.711506 0.000389649 0.702677" mass="4.714" diaginertia="0.0648213 0.0565803 0.0169323" />
<joint name="floating_base" type="free" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="trunk" />
<geom size="0.1335 0.097 0.057" type="box" rgba="0.913725 0.913725 0.847059 0" />
<geom size="0.0005 0.0005 0.0005" type="box" contype="0" conaffinity="0" group="1" rgba="0.8 0 0 0" />
<geom size="0.0005 0.0005 0.0005" type="box" rgba="0.8 0 0 0" />
<body name="FR_hip" pos="0.183 -0.047 0">
<inertial pos="-0.003311 -0.000635 3.1e-05" quat="0.507528 0.506268 0.491507 0.494499" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
<geom quat="0 1 0 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
<geom size="0.04 0.04" pos="0 -0.055 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
<body name="FR_thigh" pos="0 -0.08505 0">
<inertial pos="-0.003237 0.022327 -0.027326" quat="0.999125 -0.00256393 -0.0409531 -0.00806091" mass="1.013" diaginertia="0.00555739 0.00513936 0.00133944" />
<joint name="FR_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh_mirror" />
<geom size="0.1 0.01225 0.017" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
<body name="FR_calf" pos="0 0 -0.2">
<inertial pos="0.00472659 0 -0.131975" quat="0.706886 0.017653 0.017653 0.706886" mass="0.226" diaginertia="0.00340344 0.00339393 3.54834e-05" />
<joint name="FR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.1 0.008 0.008" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.01" pos="0 0 -0.2" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.02" pos="0 0 -0.2" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="FL_hip" pos="0.183 0.047 0">
<inertial pos="-0.003311 0.000635 3.1e-05" quat="0.494499 0.491507 0.506268 0.507528" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
<joint name="FL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
<geom size="0.04 0.04" pos="0 0.055 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
<body name="FL_thigh" pos="0 0.08505 0">
<inertial pos="-0.003237 -0.022327 -0.027326" quat="0.999125 0.00256393 -0.0409531 0.00806091" mass="1.013" diaginertia="0.00555739 0.00513936 0.00133944" />
<joint name="FL_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh" />
<geom size="0.1 0.01225 0.017" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
<body name="FL_calf" pos="0 0 -0.2">
<inertial pos="0.00472659 0 -0.131975" quat="0.706886 0.017653 0.017653 0.706886" mass="0.226" diaginertia="0.00340344 0.00339393 3.54834e-05" />
<joint name="FL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.1 0.008 0.008" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.01" pos="0 0 -0.2" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.02" pos="0 0 -0.2" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="RR_hip" pos="-0.183 -0.047 0">
<inertial pos="0.003311 -0.000635 3.1e-05" quat="0.491507 0.494499 0.507528 0.506268" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
<joint name="RR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
<geom quat="0 0 0 -1" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
<geom size="0.04 0.04" pos="0 -0.055 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
<body name="RR_thigh" pos="0 -0.08505 0">
<inertial pos="-0.003237 0.022327 -0.027326" quat="0.999125 -0.00256393 -0.0409531 -0.00806091" mass="1.013" diaginertia="0.00555739 0.00513936 0.00133944" />
<joint name="RR_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh_mirror" />
<geom size="0.1 0.01225 0.017" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
<body name="RR_calf" pos="0 0 -0.2">
<inertial pos="0.00472659 0 -0.131975" quat="0.706886 0.017653 0.017653 0.706886" mass="0.226" diaginertia="0.00340344 0.00339393 3.54834e-05" />
<joint name="RR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.1 0.008 0.008" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.01" pos="0 0 -0.2" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.02" pos="0 0 -0.2" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="RL_hip" pos="-0.183 0.047 0">
<inertial pos="0.003311 0.000635 3.1e-05" quat="0.506268 0.507528 0.494499 0.491507" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
<joint name="RL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
<geom quat="0 0 1 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
<geom size="0.04 0.04" pos="0 0.055 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
<body name="RL_thigh" pos="0 0.08505 0">
<inertial pos="-0.003237 -0.022327 -0.027326" quat="0.999125 0.00256393 -0.0409531 0.00806091" mass="1.013" diaginertia="0.00555739 0.00513936 0.00133944" />
<joint name="RL_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh" />
<geom size="0.1 0.01225 0.017" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
<body name="RL_calf" pos="0 0 -0.2">
<inertial pos="0.00472659 0 -0.131975" quat="0.706886 0.017653 0.017653 0.706886" mass="0.226" diaginertia="0.00340344 0.00339393 3.54834e-05" />
<joint name="RL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.1 0.008 0.008" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.01" pos="0 0 -0.2" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.02" pos="0 0 -0.2" rgba="0 0 0 1" />
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<!--
<position joint="FR_hip_joint" kp="1000"/>
<position joint="FR_thigh_joint" kp="1000"/>
<position joint="FR_calf_joint" kp="1000"/>
<position joint="FL_hip_joint" kp="1000"/>
<position joint="FL_thigh_joint" kp="1000"/>
<position joint="FL_calf_joint" kp="1000"/>
<position joint="RR_hip_joint" kp="1000"/>
<position joint="RR_thigh_joint" kp="1000"/>
<position joint="RR_calf_joint" kp="1000"/>
<position joint="RL_hip_joint" kp="1000"/>
<position joint="RL_thigh_joint" kp="1000"/>
<position joint="RL_calf_joint" kp="1000"/> -->
<motor name="FR_hip" gear="9.1" joint="FR_hip_joint" forcerange="-33.5 33.5" />
<motor name="FR_thigh" gear="9.1" joint="FR_thigh_joint" forcerange="-33.5 33.5" />
<motor name="FR_calf" gear="9.1" joint="FR_calf_joint" forcerange="-33.5 33.5" />
<motor name="FL_hip" gear="9.1" joint="FL_hip_joint" forcerange="-33.5 33.5" />
<motor name="FL_thigh" gear="9.1" joint="FL_thigh_joint" forcerange="-33.5 33.5" />
<motor name="FL_calf" gear="9.1" joint="FL_calf_joint" forcerange="-33.5 33.5" />
<motor name="RR_hip" gear="9.1" joint="RR_hip_joint" forcerange="-33.5 33.5" />
<motor name="RR_thigh" gear="9.1" joint="RR_thigh_joint" forcerange="-33.5 33.5" />
<motor name="RR_calf" gear="9.1" joint="RR_calf_joint" forcerange="-33.5 33.5" />
<motor name="RL_hip" gear="9.1" joint="RL_hip_joint" forcerange="-33.5 33.5" />
<motor name="RL_thigh" gear="9.1" joint="RL_thigh_joint" forcerange="-33.5 33.5" />
<motor name="RL_calf" gear="9.1" joint="RL_calf_joint" forcerange="-33.5 33.5" />
</actuator>
</mujoco>

Binary file not shown.

BIN
data/aliengo/meshes/hip.stl Normal file

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,718 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="aliengo_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="silver">
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<!-- <xacro:include filename="$(find aliengo_gazebo)/launch/gazebo.xacro"/> -->
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
<!-- <xacro:if value="$(arg DEBUG)">
<link name="world"/>
<joint name="base_static_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base"/>
</joint>
</xacro:if> -->
<link name="base">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<joint name="floating_base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base"/>
<child link="trunk"/>
</joint>
<link name="trunk">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/trunk.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.647 0.15 0.112"/>
</geometry>
</collision>
<!-- <collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/trunk.stl" scale="1 1 1"/>
</geometry>
</collision> -->
<inertial>
<origin rpy="0 0 0" xyz="0.008465 0.004045 -0.000763"/>
<mass value="9.041"/>
<inertia ixx="0.033260231" ixy="-0.000451628" ixz="0.000487603" iyy="0.16117211" iyz="4.8356e-05" izz="0.17460442"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="trunk"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
</link>
<joint name="FR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.2399 -0.051 0"/>
<parent link="trunk"/>
<child link="FR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" lower="-1.2217304764" upper="1.2217304764" velocity="40"/>
</joint>
<link name="FR_hip">
<visual>
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 -0.083 0"/>
<geometry>
<cylinder length="0.0418" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.022191 -0.015144 -1.5e-05"/>
<mass value="1.993"/>
<inertia ixx="0.002903894" ixy="7.185e-05" ixz="-1.262e-06" iyy="0.004907517" iyz="1.75e-06" izz="0.005586944"/>
</inertial>
</link>
<!-- <joint name="${name}_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_shoulder"/>
</joint> -->
<!-- this link is only for collision -->
<!-- <link name="${name}_thigh_shoulder">
<collision>
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
</geometry>
</collision>
</link> -->
<joint name="FR_thigh_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 -0.083 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" velocity="40"/>
</joint>
<link name="FR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.0374 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.005607 0.003877 -0.048199"/>
<mass value="0.639"/>
<inertia ixx="0.005666803" ixy="-3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="-1.0086e-05" izz="0.000369811"/>
</inertial>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FR_thigh"/>
<child link="FR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" lower="-2.77507351067" upper="-0.645771823238" velocity="40"/>
</joint>
<link name="FR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.0208 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
<mass value="0.207"/>
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
</inertial>
</link>
<joint name="FR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FR_calf"/>
<child link="FR_foot"/>
</joint>
<link name="FR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0165"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0265"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
</inertial>
</link>
<transmission name="FR_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="FL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.2399 0.051 0"/>
<parent link="trunk"/>
<child link="FL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" lower="-1.2217304764" upper="1.2217304764" velocity="40"/>
</joint>
<link name="FL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0.083 0"/>
<geometry>
<cylinder length="0.0418" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.022191 0.015144 -1.5e-05"/>
<mass value="1.993"/>
<inertia ixx="0.002903894" ixy="-7.185e-05" ixz="-1.262e-06" iyy="0.004907517" iyz="-1.75e-06" izz="0.005586944"/>
</inertial>
</link>
<!-- <joint name="${name}_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_shoulder"/>
</joint> -->
<!-- this link is only for collision -->
<!-- <link name="${name}_thigh_shoulder">
<collision>
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
</geometry>
</collision>
</link> -->
<joint name="FL_thigh_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0.083 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" velocity="40"/>
</joint>
<link name="FL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.0374 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.005607 -0.003877 -0.048199"/>
<mass value="0.639"/>
<inertia ixx="0.005666803" ixy="3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="1.0086e-05" izz="0.000369811"/>
</inertial>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FL_thigh"/>
<child link="FL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" lower="-2.77507351067" upper="-0.645771823238" velocity="40"/>
</joint>
<link name="FL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.0208 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
<mass value="0.207"/>
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
</inertial>
</link>
<joint name="FL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FL_calf"/>
<child link="FL_foot"/>
</joint>
<link name="FL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0165"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0265"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
</inertial>
</link>
<transmission name="FL_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="RR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.2399 -0.051 0"/>
<parent link="trunk"/>
<child link="RR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" lower="-1.2217304764" upper="1.2217304764" velocity="40"/>
</joint>
<link name="RR_hip">
<visual>
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 -0.083 0"/>
<geometry>
<cylinder length="0.0418" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.022191 -0.015144 -1.5e-05"/>
<mass value="1.993"/>
<inertia ixx="0.002903894" ixy="-7.185e-05" ixz="1.262e-06" iyy="0.004907517" iyz="1.75e-06" izz="0.005586944"/>
</inertial>
</link>
<!-- <joint name="${name}_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_shoulder"/>
</joint> -->
<!-- this link is only for collision -->
<!-- <link name="${name}_thigh_shoulder">
<collision>
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
</geometry>
</collision>
</link> -->
<joint name="RR_thigh_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 -0.083 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" velocity="40"/>
</joint>
<link name="RR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.0374 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.005607 0.003877 -0.048199"/>
<mass value="0.639"/>
<inertia ixx="0.005666803" ixy="-3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="-1.0086e-05" izz="0.000369811"/>
</inertial>
</link>
<joint name="RR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RR_thigh"/>
<child link="RR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" lower="-2.77507351067" upper="-0.645771823238" velocity="40"/>
</joint>
<link name="RR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.0208 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
<mass value="0.207"/>
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
</inertial>
</link>
<joint name="RR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RR_calf"/>
<child link="RR_foot"/>
</joint>
<link name="RR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0165"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0265"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
</inertial>
</link>
<transmission name="RR_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RR_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RR_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="RL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.2399 0.051 0"/>
<parent link="trunk"/>
<child link="RL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" lower="-1.2217304764" upper="1.2217304764" velocity="40"/>
</joint>
<link name="RL_hip">
<visual>
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0.083 0"/>
<geometry>
<cylinder length="0.0418" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.022191 0.015144 -1.5e-05"/>
<mass value="1.993"/>
<inertia ixx="0.002903894" ixy="7.185e-05" ixz="1.262e-06" iyy="0.004907517" iyz="-1.75e-06" izz="0.005586944"/>
</inertial>
</link>
<!-- <joint name="${name}_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 ${(thigh_shoulder_length/2.0+hip_offset)*mirror} 0"/>
<parent link="${name}_hip"/>
<child link="${name}_thigh_shoulder"/>
</joint> -->
<!-- this link is only for collision -->
<!-- <link name="${name}_thigh_shoulder">
<collision>
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thigh_shoulder_length}" radius="${thigh_shoulder_radius}"/>
</geometry>
</collision>
</link> -->
<joint name="RL_thigh_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0.083 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" velocity="40"/>
</joint>
<link name="RL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.0374 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.005607 -0.003877 -0.048199"/>
<mass value="0.639"/>
<inertia ixx="0.005666803" ixy="3.597e-06" ixz="0.000491446" iyy="0.005847229" iyz="1.0086e-05" izz="0.000369811"/>
</inertial>
</link>
<joint name="RL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RL_thigh"/>
<child link="RL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="44.4" lower="-2.77507351067" upper="-0.645771823238" velocity="40"/>
</joint>
<link name="RL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.0208 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.002781 6.3e-05 -0.142518"/>
<mass value="0.207"/>
<inertia ixx="0.006341369" ixy="-3e-09" ixz="-8.7951e-05" iyy="0.006355157" iyz="-1.336e-06" izz="3.9188e-05"/>
</inertial>
</link>
<joint name="RL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RL_calf"/>
<child link="RL_foot"/>
</joint>
<link name="RL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0165"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0265"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
</inertial>
</link>
<transmission name="RL_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RL_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RL_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
</robot>

Binary file not shown.

BIN
data/laikago/meshes/hip.stl Normal file

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,393 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="laikago_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="silver">
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<link name="trunk">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/trunk.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.01675"/>
<geometry>
<box size="0.5616 0.172 0.1875"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.002284 -4.1e-05 0.025165"/>
<mass value="13.733"/>
<inertia ixx="0.073348887" ixy="0.00030338" ixz="0.001918218" iyy="0.250684593" iyz="-7.5402e-05" izz="0.254469458"/>
</inertial>
</link>
<joint name="FR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.21935 -0.0875 0"/>
<parent link="trunk"/>
<child link="FR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-1.0471975512" upper="0.872664625997" velocity="52.4"/>
</joint>
<link name="FR_hip">
<visual>
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0.021 0"/>
<geometry>
<cylinder length="0.08" radius="0.041"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.001568 0.008134 0.000864"/>
<mass value="1.096"/>
<inertia ixx="0.000822113" ixy="4.982e-06" ixz="-3.672e-05" iyy="0.000983196" iyz="-2.811e-06" izz="0.000864753"/>
</inertial>
</link>
<joint name="FR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.037 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
</joint>
<link name="FR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.034 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000482 -0.02001 -0.031996"/>
<mass value="1.528"/>
<inertia ixx="0.00991611" ixy="-1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="8.511e-05" izz="0.00178256"/>
</inertial>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FR_thigh"/>
<child link="FR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
</joint>
<link name="FR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
<mass value="0.241"/>
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
</inertial>
</link>
<joint name="FL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.21935 0.0875 0"/>
<parent link="trunk"/>
<child link="FL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-0.872664625997" upper="1.0471975512" velocity="52.4"/>
</joint>
<link name="FL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 -0.021 0"/>
<geometry>
<cylinder length="0.08" radius="0.041"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.001568 -0.008134 0.000864"/>
<mass value="1.096"/>
<inertia ixx="0.000822113" ixy="-4.982e-06" ixz="-3.672e-05" iyy="0.000983196" iyz="2.811e-06" izz="0.000864753"/>
</inertial>
</link>
<joint name="FL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.037 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
</joint>
<link name="FL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.034 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000482 0.02001 -0.031996"/>
<mass value="1.528"/>
<inertia ixx="0.00991611" ixy="1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="-8.511e-05" izz="0.00178256"/>
</inertial>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FL_thigh"/>
<child link="FL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
</joint>
<link name="FL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
<mass value="0.241"/>
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
</inertial>
</link>
<joint name="RR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.21935 -0.0875 0"/>
<parent link="trunk"/>
<child link="RR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-1.0471975512" upper="0.872664625997" velocity="52.4"/>
</joint>
<link name="RR_hip">
<visual>
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0.021 0"/>
<geometry>
<cylinder length="0.08" radius="0.041"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.001568 0.008134 0.000864"/>
<mass value="1.096"/>
<inertia ixx="0.000822113" ixy="-4.982e-06" ixz="3.672e-05" iyy="0.000983196" iyz="-2.811e-06" izz="0.000864753"/>
</inertial>
</link>
<joint name="RR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.037 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
</joint>
<link name="RR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.034 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000482 -0.02001 -0.031996"/>
<mass value="1.528"/>
<inertia ixx="0.00991611" ixy="-1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="8.511e-05" izz="0.00178256"/>
</inertial>
</link>
<joint name="RR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RR_thigh"/>
<child link="RR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
</joint>
<link name="RR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
<mass value="0.241"/>
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
</inertial>
</link>
<joint name="RL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.21935 0.0875 0"/>
<parent link="trunk"/>
<child link="RL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-0.872664625997" upper="1.0471975512" velocity="52.4"/>
</joint>
<link name="RL_hip">
<visual>
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 -0.021 0"/>
<geometry>
<cylinder length="0.08" radius="0.041"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.001568 -0.008134 0.000864"/>
<mass value="1.096"/>
<inertia ixx="0.000822113" ixy="4.982e-06" ixz="3.672e-05" iyy="0.000983196" iyz="2.811e-06" izz="0.000864753"/>
</inertial>
</link>
<joint name="RL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.037 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
</joint>
<link name="RL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.034 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000482 0.02001 -0.031996"/>
<mass value="1.528"/>
<inertia ixx="0.00991611" ixy="1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="-8.511e-05" izz="0.00178256"/>
</inertial>
</link>
<joint name="RL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RL_thigh"/>
<child link="RL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
</joint>
<link name="RL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
<mass value="0.241"/>
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
</inertial>
</link>
</robot>

90
mujoco_py_test.py Normal file
View File

@ -0,0 +1,90 @@
#!/usr/bin/env python3
"""
Shows how to toss a capsule to a container.
"""
from re import T
from mujoco_py import load_model_from_path, MjSim, MjViewer
import os
import math
import keyboard
model = load_model_from_path("/home/bobzhu/Unitree/Mujoco/unitree_mujoco_git/unitree_mujoco/data/a1/urdf/a1.xml")
sim = MjSim(model)
viewer = MjViewer(sim)
sim_state = sim.get_state()
i = 0
if_increase = True
desired_speed = [0.0] * 12
desired_pos = [0.0] * 12
Kp_vel= 7.0
Ki_vel = 0.8
Kp_pos= 10.0
q_vel_former = [0.0] * 12
speed_command = [0.0] * 12
speed_error = [0.0] * 12
speed_error_former = [0.0] * 12
angle_error = [0.0] * 12
k = 0
increase = True
while True:
#sim.set_state(sim_state)
# if k > 50:
# increase = False
# elif k < -50:
# increase = True
# if increase:
# k+=1
# else:
# k-=1
# # print(desired_pos)
# for i in range(12):
# desired_pos[i] = 0.0
# q_pos_meas = sim.data.get_joint_qpos(sim.model.joint_names[i])
# angle_error[i] = desired_pos[i] - q_pos_meas
# if angle_error[i] < - math.pi:
# angle_error[i] = 2 * math.pi + angle_error[i]
# elif angle_error[i] >= math.pi:
# angle_error[i] = angle_error[i] - 2 * math.pi
# desired_speed[i] = Kp_pos * angle_error[i]
# q_vel_meas = sim.data.get_joint_qvel(sim.model.joint_names[i])
# #print(sim.data.get_joint_qvel(sim.model.joint_names[0]))
# speed_error[i] = desired_speed[i] - q_vel_meas
# speed_command[i] += Kp_vel * (speed_error[i] - speed_error_former[i]) + Ki_vel * speed_error[i]
# speed_error_former[i] = speed_error[i]
# if speed_command[i] > 33.5:
# speed_command[i] = 33.5
# elif speed_command[i] < -33.5:
# speed_command[i] = -33.5
# sim.data.ctrl[i] = speed_command[i]
#sim.data.ctrl[:] = k / 10
#print(joint_name, sim.data.get_joint_qpos(joint_name), sim.data.get_joint_qvel(joint_name))
sim.step()
viewer.render()
#print(" ")
if os.getenv('TESTING') is not None:
break