<transmission name="bhand_${joint}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="bhand_${joint}">
- <hardwareInterface>PositionJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="bhand_${joint}_actuator">
- <hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="bhand_${joint}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="bhand_${joint}">
- <hardwareInterface>PositionJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="bhand_${joint}_actuator">
- <hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="bhand_${joint}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="bhand_${joint}">
- <hardwareInterface>PositionJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="bhand_${joint}_actuator">
- <hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="j1_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wam_joint_1">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="j1_motor">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>42.0</mechanicalReduction>
</actuator>
</transmission>
<transmission name="j2_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wam_joint_2">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="j2_motor">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>28.25</mechanicalReduction>
</actuator>
</transmission>
<transmission name="j3_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wam_joint_3">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="j3_motor">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>28.25</mechanicalReduction>
</actuator>
</transmission>
<transmission name="j4_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wam_joint_4">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
+ <hardwareInterface>hardwaware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="j4_motor">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="j5_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wam_joint_5">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="j5_motor">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>9.48</mechanicalReduction>
</actuator>
</transmission>
<transmission name="j6_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wam_joint_6">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="j6_motor">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>9.48</mechanicalReduction>
</actuator>
</transmission>
<transmission name="j7_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wam_joint_7">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="j7_motor">
- <hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>14.93</mechanicalReduction>
</actuator>
</transmission>