42 lines
1.7 KiB
XML
42 lines
1.7 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
|
|
<xacro:macro name="leg_transmission" params="name">
|
|
|
|
<transmission name="${name}_abad_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="${name}_abad_joint">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="${name}_abad_motor">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>"${abadGearRatio}"</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="${name}_hip_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="${name}_hip_joint">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="${name}_hip_motor">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>"${abadGearRatio}"</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="${name}_knee_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="${name}_knee_joint">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="${name}_knee_motor">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>"${kneeGearRatio}"</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
</xacro:macro>
|
|
|
|
</robot>
|