ROS2 Control transmission_interface说明
文章目录
前言
transmission_interface 1 2提供了一个基类和一些插件的实现,这些插件可以被自定义硬件组件集成和加载。它们不会被任何硬件组件或 gazebo 插件自动加载,每个硬件组件负责加载适当的传动接口,将执行器读数映射为关节读数。
正文
目前已经实现的变换接口有下边3类:
SimpleTransmission: 一个简单的传动,具有恒定的减速比且没有额外的动力学DifferentialTransmission: 一个具有两个执行器和两个关节的差动传动FourBarLinkageTransmission: 一个具有两个执行器和两个关节的四连杆传动
SimpleTransmission 简单传动
简单传动主要有两种,皮带轮和齿轮,传动比与半径直接相关,但是皮带轮方向与执行器方向一致,齿轮与传动轮顺逆时针相反。
配置
完整配置文件 /ros2_control_demo_example_8/description/ros2_control/rrbot_transmissions_system_position_only.ros2_control.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rrbot_transmissions_system_position_only" params="name prefix slowdown:=2.0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>ros2_control_demo_example_8/RRBotTransmissionsSystemPositionOnlyHardware</plugin>
<param name="actuator_slowdown">${slowdown}</param>
</hardware>
<joint name="${prefix}joint1">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<joint name="${prefix}joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<transmission name="transmission1">
<plugin>transmission_interface/SimpleTransmission</plugin>
<actuator name="actuator1" role="actuator1"/>
<joint name="joint1" role="joint1">
<mechanical_reduction>2.0</mechanical_reduction>
<offset>0.0</offset>
</joint>
</transmission>
<transmission name="transmission2">
<plugin>transmission_interface/SimpleTransmission</plugin>
<actuator name="actuator2" role="actuator2"/>
<joint name="joint2" role="joint2">
<mechanical_reduction>4.0</mechanical_reduction>
<offset>0.0</offset>
</joint>
</transmission>
</ros2_control>
</xacro:macro>
</robot>
其中actuator1和joint1的传动关系描述如下
<transmission name="transmission1">
<plugin>transmission_interface/SimpleTransmission</plugin>
<actuator name="actuator1" role="actuator1"/>
<joint name="joint1" role="joint1">
<mechanical_reduction>2.0</mechanical_reduction>
<offset>0.0</offset>
</joint>
</transmission>
图示

DifferentialTransmission 差速传动
配置
<?xml version="1.0"?>
<robot name="robot" xmlns="http://www.ros.org">
<ros2_control name="FullSpec" type="system">
<joint name="joint1">
<command_interface name="velocity">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</command_interface>
<state_interface name="velocity"/>
</joint>
<joint name="joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<transmission name="transmission1">
<plugin>transmission_interface/DifferentialTransmission</plugin>
<actuator name="joint1_motor" role="actuator1">
<mechanical_reduction>50</mechanical_reduction>
</actuator>
<actuator name="joint2_motor" role="actuator2">
<mechanical_reduction>-50</mechanical_reduction>
</actuator>
<joint name="joint1" role="joint1">
<offset>0.5</offset>
<mechanical_reduction>2.0</mechanical_reduction>
</joint>
<joint name="joint2" role="joint2">
<offset>-0.5</offset>
<mechanical_reduction>-2.0</mechanical_reduction>
</joint>
</transmission>
</ros2_control>
</robot>
其中actuator1、joint1、actuator2、joint2的传动关系描述如下
<transmission name="transmission1">
<plugin>transmission_interface/DifferentialTransmission</plugin>
<actuator name="joint1_motor" role="actuator1">
<mechanical_reduction>50</mechanical_reduction>
</actuator>
<actuator name="joint2_motor" role="actuator2">
<mechanical_reduction>-50</mechanical_reduction>
</actuator>
<joint name="joint1" role="joint1">
<offset>0.5</offset>
<mechanical_reduction>2.0</mechanical_reduction>
</joint>
<joint name="joint2" role="joint2">
<offset>-0.5</offset>
<mechanical_reduction>-2.0</mechanical_reduction>
</joint>
</transmission>
图示

FourBarLinkageTransmission 四连杆传动
配置
<?xml version="1.0"?>
<robot name="robot" xmlns="http://www.ros.org">
<ros2_control name="FullSpec" type="system">
<joint name="joint1">
<command_interface name="velocity">
<param name="min">-0.5</param>
<param name="max">0.5</param>
</command_interface>
<state_interface name="velocity"/>
</joint>
<joint name="joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<transmission name="transmission1">
<plugin>transmission_interface/FourBarLinkageTransmission</plugin>
<actuator name="joint1_motor" role="actuator1">
<mechanical_reduction>50</mechanical_reduction>
</actuator>
<actuator name="joint2_motor" role="actuator2">
<mechanical_reduction>-50</mechanical_reduction>
</actuator>
<joint name="joint1" role="joint1">
<offset>0.5</offset>
<mechanical_reduction>2.0</mechanical_reduction>
</joint>
<joint name="joint2" role="joint2">
<offset>-0.5</offset>
<mechanical_reduction>-2.0</mechanical_reduction>
</joint>
</transmission>
</ros2_control>
</robot>
其中actuator1、joint1、actuator2、joint2的传动关系描述如下
<transmission name="transmission1">
<plugin>transmission_interface/FourBarLinkageTransmission</plugin>
<actuator name="joint1_motor" role="actuator1">
<mechanical_reduction>50</mechanical_reduction>
</actuator>
<actuator name="joint2_motor" role="actuator2">
<mechanical_reduction>-50</mechanical_reduction>
</actuator>
<joint name="joint1" role="joint1">
<offset>0.5</offset>
<mechanical_reduction>2.0</mechanical_reduction>
</joint>
<joint name="joint2" role="joint2">
<offset>-0.5</offset>
<mechanical_reduction>-2.0</mechanical_reduction>
</joint>
</transmission>
图示

总结
目前没有在中文论坛搜到完整对于这一部分的说明,所以对外网资料做了一下梳理,具体测试效果待后续完成后再写一篇文章。
1215

被折叠的 条评论
为什么被折叠?



