unitree_ros/robots/g1_description/xacro/arm_transmission.xacro

64 lines
2.9 KiB
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="arm_transmission" params="name">
<transmission name="${name}_shoulder_pitch_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_shoulder_pitch_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_shoulder_pitch_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_shoulder_roll_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_shoulder_roll_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_shoulder_roll_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_shoulder_yaw_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_shoulder_yaw_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_shoulder_yaw_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_elbow_pitch_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_elbow_pitch_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_elbow_pitch_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${name}_elbow_roll_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_elbow_roll_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_elbow_roll_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
</robot>