PIBOT移植ROS2记录(2)-添加Node与cmd_vel

前文添加了简单的测试保证编译通过,本文将开始移植实现一个控制下发

1. base_driver的移植

  • 首先把base_driver.cpp添加到pibot_driver中编译
diff --git a/CMakeLists.txt b/CMakeLists.txt
index c1a7568..ea8fa95 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -10,6 +10,7 @@ find_package(ament_cmake REQUIRED)
 find_package(rclcpp REQUIRED)
 
 add_executable(pibot_driver src/main.cpp
+                            src/base_driver.cpp
                       )
  • 注释ROS1相关以及大部分影响编译的函数实现
    如替换#include <ros/ros.h>----> #include <rclcpp/rclcpp.hpp>
/home/pibot/ros2_ws/src/pibot_bringup/src/base_driver.cpp:1:10: fatal error: base_driver.h: No such file or directory

需要在cmake新增include_directories目录

include_directories(
  include include
)

同时#include "base_driver.h"修改为#include "pibot_bringup/base_driver.h"

2. 实现Node

ROS2中编译一个node,需要从rclcpp::Node继承,我们删除BaseDriver中的单例,并添加至从rclcpp::Node继承

3. 实例化Node

在main中添加Node实例,并调用loop

#include "pibot_bringup/base_driver.h"

int main(int argc, char* argv[]) {
  rclcpp::init(argc, argv);

  auto driver = std::make_shared<BaseDriver>();
  driver->work_loop();
  
  rclcpp::shutdown();

  return 0;
}
  • 工作线程运行
    在loop中修改
    ros::Rate----->rclcpp::WallRate
    ros::ok----->rclcpp::ok
void BaseDriver::work_loop() {
  // ros::Rate loop(bdg.freq);
  rclcpp::WallRate loop(100);
  while (rclcpp::ok()) {
    //     update_param();

    //     update_odom();

    //     update_pid_debug();

    //     update_speed();

    //     if (bdg.use_imu) {
    //         if (Data_holder::get()->parameter.imu_type == IMU_TYPE_GY65
    //             || Data_holder::get()->parameter.imu_type == IMU_TYPE_GY85
    //             || Data_holder::get()->parameter.imu_type == IMU_TYPE_GY87) {
    //             update_imu();
    //         }
    //     }

    loop.sleep();
  }
}
  • 替换日志输出
ROS_INFO--->RCLCPP_INFO
ROS_WARN--->RCLCPP_WARN
ROS_ERROR--->RCLCPP_ERROR

RCLCPP_XXX接受一个参数标识, Node类中直接使用this->get_logger(),如
RCLCPP_INFO(this->get_logger(), "BaseDriver startup...");

4. 添加cmd_vel的订阅

cmd_vel为标准的速度消息,订阅后转换为串口命令发送给下位机
订阅消息

  cmd_vel_sub_ = this->create_subscription<geometry_msgs::msg::Twist>("/cmd_vel", // 配置后面移植,先硬编代替
                                                                      10,
                                                                      std::bind(&BaseDriver::cmd_vel_callback, this, std::placeholders::_1));

返回值定义

  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;

头文件#include <geometry_msgs/Twist.h>---->`

include <geometry_msgs/msg/twist.hpp>`

订阅函数subscribe---->create_subscription
订阅返回类型ros::Subscriber---->rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
消息类型(回调参数类型)geometry_msgs::Twist---->geometry_msgs::msg::Twist

ROS1到ROS2的很多消息定义类似,大部分一样只是多了一个msg域

至此消息定义已添加完成,使用colcon --log-base /dev/null build --symlink-install --event-handlers console_direct+ log-编译可以看到,出现了链接错误,显然少了依赖项目

在CMakeLists.txt添加geometry_msgs的依赖即可正常编译

find_package(geometry_msgs REQUIRED)
...
ament_target_dependencies(pibot_driver 
                      rclcpp
                      geometry_msgs)

5. 运行测试

尝试ros2 run运行该node, 提示找不到包

➜  ros2 run pibot_bringup pibot_driver        
Package 'pibot_bringup' not found

由ROS1的经验,我们执行这里需要生效环境变量,执行. install/setup.bash再次运行我们可以看到日志输出

➜  . install/setup.bash
➜  ros2 run pibot_bringup pibot_driver
[INFO] [1651597084.976378233] [pibot_dirver]: BaseDriver startup...
[INFO] [1651597084.976500411] [pibot_dirver]: subscribe cmd topic on [/cmd_vel]
[INFO] [1651597086.171644990] [pibot_dirver]: init ok

打开另外的终端输入ros2 topic listros2 topic info /cmd_vel可以查看订阅的topic信息

➜  ros2 topic list         
/cmd_vel
/parameter_events
/rosout
➜  ros2 topic info /cmd_vel
Type: geometry_msgs/msg/Twist
Publisher count: 0
Subscription count: 1

可以使用下面命令发布消息

ros2_ws ros2 topic pub --rate 20 /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.5, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 1.0}}"
[INFO] [1651597691.617713960] [pibot_dirver]: cmd_vel:[0.500 0.000 1.200]
[INFO] [1651597691.667825693] [pibot_dirver]: cmd_vel:[0.500 0.000 1.200]
[INFO] [1651597691.717775974] [pibot_dirver]: cmd_vel:[0.500 0.000 1.200]

可以看到pibot_driver接收到订阅的callback,时间间隔为50ms

本文代码https://gitee.com/pibot/pibot_bringup/tree/bc942bdb49ec5a358a0a13f8359eb5e7878e2350

最后编辑于
©著作权归作者所有,转载或内容合作请联系作者
  • 序言:七十年代末,一起剥皮案震惊了整个滨河市,随后出现的几起案子,更是在滨河造成了极大的恐慌,老刑警刘岩,带你破解...
    沈念sama阅读 204,053评论 6 478
  • 序言:滨河连续发生了三起死亡事件,死亡现场离奇诡异,居然都是意外死亡,警方通过查阅死者的电脑和手机,发现死者居然都...
    沈念sama阅读 85,527评论 2 381
  • 文/潘晓璐 我一进店门,熙熙楼的掌柜王于贵愁眉苦脸地迎上来,“玉大人,你说我怎么就摊上这事。” “怎么了?”我有些...
    开封第一讲书人阅读 150,779评论 0 337
  • 文/不坏的土叔 我叫张陵,是天一观的道长。 经常有香客问我,道长,这世上最难降的妖魔是什么? 我笑而不...
    开封第一讲书人阅读 54,685评论 1 276
  • 正文 为了忘掉前任,我火速办了婚礼,结果婚礼上,老公的妹妹穿的比我还像新娘。我一直安慰自己,他们只是感情好,可当我...
    茶点故事阅读 63,699评论 5 366
  • 文/花漫 我一把揭开白布。 她就那样静静地躺着,像睡着了一般。 火红的嫁衣衬着肌肤如雪。 梳的纹丝不乱的头发上,一...
    开封第一讲书人阅读 48,609评论 1 281
  • 那天,我揣着相机与录音,去河边找鬼。 笑死,一个胖子当着我的面吹牛,可吹牛的内容都是我干的。 我是一名探鬼主播,决...
    沈念sama阅读 37,989评论 3 396
  • 文/苍兰香墨 我猛地睁开眼,长吁一口气:“原来是场噩梦啊……” “哼!你这毒妇竟也来了?” 一声冷哼从身侧响起,我...
    开封第一讲书人阅读 36,654评论 0 258
  • 序言:老挝万荣一对情侣失踪,失踪者是张志新(化名)和其女友刘颖,没想到半个月后,有当地人在树林里发现了一具尸体,经...
    沈念sama阅读 40,890评论 1 298
  • 正文 独居荒郊野岭守林人离奇死亡,尸身上长有42处带血的脓包…… 初始之章·张勋 以下内容为张勋视角 年9月15日...
    茶点故事阅读 35,634评论 2 321
  • 正文 我和宋清朗相恋三年,在试婚纱的时候发现自己被绿了。 大学时的朋友给我发了我未婚夫和他白月光在一起吃饭的照片。...
    茶点故事阅读 37,716评论 1 330
  • 序言:一个原本活蹦乱跳的男人离奇死亡,死状恐怖,灵堂内的尸体忽然破棺而出,到底是诈尸还是另有隐情,我是刑警宁泽,带...
    沈念sama阅读 33,394评论 4 319
  • 正文 年R本政府宣布,位于F岛的核电站,受9级特大地震影响,放射性物质发生泄漏。R本人自食恶果不足惜,却给世界环境...
    茶点故事阅读 38,976评论 3 307
  • 文/蒙蒙 一、第九天 我趴在偏房一处隐蔽的房顶上张望。 院中可真热闹,春花似锦、人声如沸。这庄子的主人今日做“春日...
    开封第一讲书人阅读 29,950评论 0 19
  • 文/苍兰香墨 我抬头看了看天上的太阳。三九已至,却和暖如春,着一层夹袄步出监牢的瞬间,已是汗流浃背。 一阵脚步声响...
    开封第一讲书人阅读 31,191评论 1 260
  • 我被黑心中介骗来泰国打工, 没想到刚下飞机就差点儿被人妖公主榨干…… 1. 我叫王不留,地道东北人。 一个月前我还...
    沈念sama阅读 44,849评论 2 349
  • 正文 我出身青楼,却偏偏与公主长得像,于是被迫代替她去往敌国和亲。 传闻我的和亲对象是个残疾皇子,可洞房花烛夜当晚...
    茶点故事阅读 42,458评论 2 342

推荐阅读更多精彩内容