mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 22:00:05 +00:00
702 lines
23 KiB
Plaintext
702 lines
23 KiB
Plaintext
|
<?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">
|
||
|
<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="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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<box size="0.267 0.194 0.114"/>
|
||
|
</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.0001" 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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder length="0.04" radius="0.046"/>
|
||
|
</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="FR_hip_fixed" type="fixed">
|
||
|
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
|
||
|
<parent link="FR_hip"/>
|
||
|
<child link="FR_thigh_shoulder"/>
|
||
|
</joint>
|
||
|
<!-- this link is only for collision -->
|
||
|
<link name="FR_thigh_shoulder">
|
||
|
<collision>
|
||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder length="0.032" radius="0.041"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="FR_thigh_joint" type="revolute">
|
||
|
<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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</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="orange"/>
|
||
|
</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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder length="0.04" radius="0.046"/>
|
||
|
</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="FL_hip_fixed" type="fixed">
|
||
|
<origin rpy="0 0 0" xyz="0 0.081 0"/>
|
||
|
<parent link="FL_hip"/>
|
||
|
<child link="FL_thigh_shoulder"/>
|
||
|
</joint>
|
||
|
<!-- this link is only for collision -->
|
||
|
<link name="FL_thigh_shoulder">
|
||
|
<collision>
|
||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder length="0.032" radius="0.041"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="FL_thigh_joint" type="revolute">
|
||
|
<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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</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="orange"/>
|
||
|
</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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder length="0.04" radius="0.046"/>
|
||
|
</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="RR_hip_fixed" type="fixed">
|
||
|
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
|
||
|
<parent link="RR_hip"/>
|
||
|
<child link="RR_thigh_shoulder"/>
|
||
|
</joint>
|
||
|
<!-- this link is only for collision -->
|
||
|
<link name="RR_thigh_shoulder">
|
||
|
<collision>
|
||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder length="0.032" radius="0.041"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="RR_thigh_joint" type="revolute">
|
||
|
<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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</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="orange"/>
|
||
|
</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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder length="0.04" radius="0.046"/>
|
||
|
</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="RL_hip_fixed" type="fixed">
|
||
|
<origin rpy="0 0 0" xyz="0 0.081 0"/>
|
||
|
<parent link="RL_hip"/>
|
||
|
<child link="RL_thigh_shoulder"/>
|
||
|
</joint>
|
||
|
<!-- this link is only for collision -->
|
||
|
<link name="RL_thigh_shoulder">
|
||
|
<collision>
|
||
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder length="0.032" radius="0.041"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="RL_thigh_joint" type="revolute">
|
||
|
<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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</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.obj" scale="1 1 1"/>
|
||
|
</geometry>
|
||
|
<material name="orange"/>
|
||
|
</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="orange"/>
|
||
|
</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>
|
||
|
|