quadruped_ros2_control/descriptions/quadruped_gazebo/urdf/common/transmission.xacro

43 lines
1.7 KiB
Plaintext
Raw Normal View History

2024-09-09 22:18:19 +08:00
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="leg_transmission" params="name">
<transmission name="${prefix}_HAA_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_HAA">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_HAA_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}_HFE_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_HFE">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_HFE_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}_KFE_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_KFE">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_KFE_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
</robot>