quadruped_ros2_control/descriptions/deep_robotics/lite3_description/xacro/transmission.xacro

36 lines
1.2 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}_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="{name}_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="{name}_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="{name}_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="{name}_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="{name}_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="{name}_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
</robot>