@TOC
前言
前文我们终于一起完成了差速小车的建模、硬件组件、控制器的编写,至此我们需要自己完成的代码部分已经基本结束,回顾绪论,我们当时说ros2-control的四个概念还有控制器管理器(Controller Manager)和硬件资源管理器(Resource Manager),这两个并不像硬件组件和控制器一样需要我们手动写,它们由官方的功能包提供,负责调用我们自己编写的动态库,也就是硬件组件和控制器。
今天我们开始最后一部分内容的学习,验证我们的代码,使得整个框架运转起来。前两节主要是代码部分,学习起来可能略感枯燥,但是也是进步的过程,因受篇幅限制,笔者没有将所有源码粘贴出来,只提出笔者自己觉得重要的几点地方来讲述,若有细节感到疑惑,可以参照教程的对应源码也完全开源供大家学习,如果您觉得对您有帮助,希望能得到个start鼓励一下: 教程开源代码
那么这一小节,我们继续我们的学习,运行控制器管理器,运行整个框架!
运行控制器管理器
环境
ros2版本 Humble
WSL2-Ubuntu-22.04
创建launch文件和参数yaml文件
控制器管理器,即是一个类,又是一个功能包。这个功能包运行的节点负责调用我们的控制器,与终端进行交互等等。我们想要运行这个功能包,还需要创建一些配置文件,这里我们用launch启动多个节点,所以在硬件组件的功能包diff_test_control
下面新建bring_up
文件夹。在bring_up
文件夹下新建config
和launch
文件夹,一个用于存放参数yaml文件,一个用于存放launch文件。
编写参数yaml文件
由于我们框架运行时至少有控制器管理器这个主节点和控制器这个生命周期节点,所以yaml文件主要为它们配置参数,
controller_manager:
ros__parameters:
update_rate: 10 # Hz
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
test_controller:
type: diff_test_controller/DiffTestController
test_controller:
ros__parameters:
left_wheel_names: ["left_wheel_joint"]
right_wheel_names: ["right_wheel_joint"]
wheel_separation: 0.10
wheels_per_side: 1 # actually 2, but both are controlled by 1 signal
wheel_radius: 0.015
linear.x.velocity_clamp: 2.0
angular.z.velocity_clamp: 1.57
首先是控制器管理器节点的参数,主要就是更新频率和用哪些控制器。test_controller
是生命周期节点的名字,type
是我们命名空间和类,这个我们在写插件的xml文件时遇到过。我们用到了两个控制器,一个是差速小车的控制器,还有一个joint_state_broadcaster
我们之前提到过,这个是官方写好的控制器,它不接收控制信号,接收所有的关节反馈,也就是state_interface
,然后以joint_state的形式发布出来,这个有利于我们可视化。接下来就是控制器的参数了,不懂ros2参数yaml文件写法的同学可以自行熟练,这里left_wheel_names
和right_wheel_names
需要和建模里面urdf的ros2-control标签中Joint
的名字一样,这个我们说控制器的时候提到过,控制器的接口就是通过名字和type找到自己对应的硬件组件接口的。
编写launch文件
我们借助launch文件需要开启的节点主要有3个,分别是控制器管理器中的控制主节点ros2_control_node
,如果你是实时Linux内核,这个节点还会自动帮你提升控制线程的优先级,保证了ros2-control运行的实时性。节点的源码大家可以看看官方GitHub:ros2_control_node源码 (github.com)
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[FindPackageShare("diff_test_control"), "urdf", "diffbot.urdf.xacro"]
),
" ",
]
)
robot_description = {"robot_description": robot_description_content}
...省略部分代码
robot_controllers = PathJoinSubstitution(
[
FindPackageShare("diff_test_control"),
"config",
"diff_controllers.yaml",
]
)
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
output="both",
)
启动主节点需要两个参数,robot_description
和robot_controllers
,前者就是我们写的参数yaml文件,后者是我们之前写的urdf,准确的说是urdf文件里面的ros2-control这个标签。不得不说,官方这张图值得仔细揣摩。
然后是robot_state_publisher
和rviz2
这两个节点,rviz2
是可视化工具,而robot_state_publisher
是向rviz2
发布机器人的模型,当然如果您不需要可视化,这两个节点也不需要开启,但是我们实验就是要看到效果嘛。
robot_state_pub_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description]
)
rviz_node = Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file],
condition=IfCondition(gui),
)
那么接着我们启动python文件
ros2 launch diff_test_control diff_test.launch.py
发现小车的模型已经加载出来了,这个是robot_state_publisher
节点起作用。
接着我们查看当前存在哪些节点
ros2 node list
我们看到了控制器管理器节点,hardware_node
是我们在硬件组件里面创建的,负责发布和接收车轮转速信息话题。说明我们的硬件组件已经加载进去了,终端打印的信息也能看到resource_manager
的logger打印出来了,选用哪个硬件组件是在urdf里面就决定了的,这个我们之前说过。
这里我补充一点,由于没有实际物理硬件,这里我把车轮控制和车轮转速信息接收两个话题设置为了一样,即认为小车控制命令下发,小车就能立即达到对应的转速,当然这是个理想的条件,仅供我们实验用。
我们发现并没有控制器的生命周期节点,这个是需要我们加载进去的。输入下面指令使控制器加载并且配置完成
ros2 control load_controller test_controller --set-state configured
终端显示加载成功,并且运行主节点ros2_control_node
的那个终端也打印出了对应信息,我们知道此时控制器还处于未激活状态,我们可以输入指令让控制器处于激活状态
ros2 control set_controller_state test_controller active
此时控制器已经完全激活,已经可以正常运行,想在RVIZ里面看见Joint的活动,我们还需要用同样的方法去激活joint_state_broadcaster
控制器。
通过终端交互,我们可以在线的切换控制器,这个在调试里面能发挥比较大的作用,比如我比较pid控制器和MPC控制器的优异。
spawner自动加载
那么到这有同学就有疑问了,假如我机器人功能都写完了,需要上电自启动了,难道控制器还要我在终端输入指令一步步去加载吗?别急,你想到的,ros2-control官方也想到了。controller_manager
里面的spawner
脚本就是用来帮助我们去自动运行控制器的,它的源码可以看这个链接:spawner.py(github.com)
我们只需在launch文件加上这个节点即可,我们在参数里面指定我们需要加载的控制器
joint_state_broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster", "--controller-manager", "controller_manager"],
)
robot_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["test_controller", "--controller-manager", "controller_manager"],
)
# Delay rviz start after `joint_state_broadcaster`
delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[rviz_node],
)
)
# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)
对了,launch文件中这些节点的启动顺序有要求的,比如rviz2
都没启动,那joint_state
发给谁看呢?,所以多加了下面几行代码。也可以看出ros2写launch可以采用python去写,是真的很灵活方便,这也是ros1不具备的功能。
接着我们启动launch文件,启动RVIZ
后,为了能看见小车的TF变换关系,我们需
修改FixedFrame为odom
添加插件,Add->Odometry->OK
选择话题,Odometry->Topic->选/odom
去除协方差显示,Odometry->Covariance>取消勾选
控制小车运动
我们在控制器里面的逻辑是,接收
~/cmd_vel
话题的Twist格式的指令,即我们需要像test_controller/cmd_vel
这个话题发布Twist格式的指令。不知道大家还记不记得最开始的键盘控制小乌龟?sudo apt install ros-humble-teleop-twist-keyboard
这个节点会监听键盘的按键事件,然后发布cmd_vel话题,我们就可以通过这个节点来控制差速小车,只需要把话题重映射一下
ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=/test_controller/cmd_vel
接着我们根据提升进行操作,首先按
U
,这个本来是让小乌龟原地转圈。可以看到
rviz2
中,我们的小车也开始转圈,说明我们的里程计和运动学逻辑都正确。大家也可以按其他按键试试看,按i
是前进。
更多具体的代码细节请参考:教程开源代码
总结
本文验证了前文所写的控制器和硬件组件,带大家认识了Controller Manager
这个重要的功能包和里面的两个重要节点,分别是ros2_control_node
和spawner
,学习了ros2-control下的参数yaml文件和launch文件的写法,并且借助小乌龟的键盘控制节点去操纵我们的差速小车。至此,借助这个小demo(貌似也不小了),我们熟悉了整个ros2-control框架的运作流程,其中不乏一些细节需要各位去源码里面探寻。
本系列教程按道理就已经结束了,如果对其中有问题不清楚,欢迎大家给我私信留言或者加入我创建的一个小的交流群QQ-536788289
写作不易,如果对您有帮助,麻烦点个star★★★加个关注吧!我会继续努力分享更多ROS2小知识
版权声明:本文为博主机器小狗史努比原创文章,未经博主允许不得转载。