719 lines
25 KiB
XML
719 lines
25 KiB
XML
<?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="package://aliengo_description/meshes/trunk.dae" 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="package://aliengo_description/meshes/trunk.dae" 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" lower="-1.2217304764" upper="1.2217304764" velocity="20"/>
|
|
</joint>
|
|
<link name="FR_hip">
|
|
<visual>
|
|
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/hip.dae" 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" velocity="20"/>
|
|
</joint>
|
|
<link name="FR_thigh">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/thigh_mirror.dae" 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="55" lower="-2.77507351067" upper="-0.645771823238" velocity="16"/>
|
|
</joint>
|
|
<link name="FR_calf">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/calf.dae" 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" lower="-1.2217304764" upper="1.2217304764" velocity="20"/>
|
|
</joint>
|
|
<link name="FL_hip">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/hip.dae" 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" velocity="20"/>
|
|
</joint>
|
|
<link name="FL_thigh">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/thigh.dae" 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="55" lower="-2.77507351067" upper="-0.645771823238" velocity="16"/>
|
|
</joint>
|
|
<link name="FL_calf">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/calf.dae" 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" lower="-1.2217304764" upper="1.2217304764" velocity="20"/>
|
|
</joint>
|
|
<link name="RR_hip">
|
|
<visual>
|
|
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/hip.dae" 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" velocity="20"/>
|
|
</joint>
|
|
<link name="RR_thigh">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/thigh_mirror.dae" 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="55" lower="-2.77507351067" upper="-0.645771823238" velocity="16"/>
|
|
</joint>
|
|
<link name="RR_calf">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/calf.dae" 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" lower="-1.2217304764" upper="1.2217304764" velocity="20"/>
|
|
</joint>
|
|
<link name="RL_hip">
|
|
<visual>
|
|
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/hip.dae" 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" velocity="20"/>
|
|
</joint>
|
|
<link name="RL_thigh">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/thigh.dae" 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="55" lower="-2.77507351067" upper="-0.645771823238" velocity="16"/>
|
|
</joint>
|
|
<link name="RL_calf">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://aliengo_description/meshes/calf.dae" 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>
|
|
|