1. 常用 API
1.1 初始化 ros::init
/** @brief ROS初始化函数
* 该函数可以解析并使用节点启动时传入的参数(通过参数设置节点名称、命名空间...)
*
* 该函数有多个重载版本,如果使用NodeHandle建议调用该版本。
*
* \param argc 封装实参个数(n + 1)
* \param argv 封装参数的数组
* \param name 节点名称,需要保证其唯一性,不允许包含命名空间
* \param options 可选,节点启动选项,被封装进了ros::init_options
*/
ros::init("argc, argv, "init_ros");
- argc 与 argv 的使用
- 如果按照 ROS 中的特定格式传入实参,那ROS可以加以使用,比如用来设置全局参数,给节点重命名
- options 的使用
- 节点名称需要保证唯一,会导致一个问题:同一个节点不能重复启动
- 结果:ROS 中当有重名节点启动时,之前的节点会被关闭
- 需求:特定场景下,需要一个节点多次启动且能正常运行,怎么办?
- 解决:设置启动项 ros::init_options::AnonymousName ,通过在节点名称后缀随机数来避免重名问题
ros::init("argc, argv, "init_ros", ros::init_options::AnonymousName);
1.2 话题与服务相关对象
- 在 roscpp 中,话题和服务的相关对象一般由 NodeHandle 创建
- NodeHandle 有一个重要作用是可以用于设置命名空间
-
发布对象
- 对象获取
/** * \brief 根据话题生成发布对象 * 在 ROS master 注册并返回一个发布者对象,该对象可以发布消息 * * 使用示例如下: * * ros::Publisher pub = handle.advertise<std_msgs::Empty>("my_topic", 1); * * \param topic 发布消息使用的话题 * * \param queue_size 队列长度,即等待发送给订阅者的最大消息数量 * * \param latch (optional) 默认为false,如果为 true,该话题发布的最后一条消息将被保存, 并且后期当有订阅者连接时会将该消息发送给订阅者 latch 设置为 true 的作用? 以静态地图发布为例 方案1:可以使用固定频率发送地图数据,但是效率低; 方案2:可以将地图发布对象的 atch 设置为 true,并且发布方只发送一次数据 每当订阅者连接时将地图数据发送给订阅者(只发送一次),这样提高了数据的发送效率 * * \return 调用成功时,会返回一个发布对象 */ template <class M> ros::Publisher pub = nh.advertise<std_msgs::String> (const std::string& topic, uint32_t queue_size, bool latch = false)
- 消息发布函数
/** * 发布消息 */ pub.publish(msg);
-
订阅对象
- 对象获取
/** * \brief 生成某个话题的订阅对象 * * 该函数将根据给定的话题在 ROS master 注册,并自动连接相同主题的发布方,每接收到一条消息,都会调用回调 * 函数,并且传入该消息的共享指针,该消息不能被修改,因为可能其他订阅对象也会使用该消息。 * * 使用示例如下: void callback(const std_msgs::Empty::ConstPtr& message) { } ros::Subscriber sub = handle.subscribe("my_topic", 1, callback); * * \param M [template] M 是指消息类型 * \param topic 订阅的话题 * \param queue_size 消息队列长度,超出长度时,头部的消息将被弃用 * \param fp 当订阅到一条消息时,需要执行的回调函数 * \return 调用成功时,返回一个订阅者对象,失败时,返回空对象 * */ template<class M> Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr<M const>&), const TransportHints& transport_hints = TransportHints())
-
服务对象
- 对象获取
/** * \brief 生成服务端对象 * * 该函数可以连接到 ROS master,并提供一个具有给定名称的服务对象。 * * 使用示例如下: bool callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::ServiceServer service = handle.advertiseService("my_service", callback); * * \param service 服务的主题名称 * \param srv_func 接收到请求时,需要处理请求的回调函数 * \return 请求成功时返回服务对象,否则返回空对象: * */ template<class MReq, class MRes> ServiceServer advertiseService(const std::string& service, bool(*srv_func)(MReq&, MRes&))
-
客户端对象
- 对象获取
/** * @brief 创建一个服务客户端对象 * * 当清除最后一个连接的引用句柄时,连接将被关闭。 * * @param service_name 服务主题名称 */ template<class Service> ServiceClient serviceClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
- 请求发送函数
/** * @brief 发送请求 * 返回值为 bool 类型,true,请求处理成功,false,处理失败。 */ template<class Service> bool call(Service& service)
- 等待服务函数
/** * ros::service::waitForService("addInts"); * \brief 等待服务可用,否则一致处于阻塞状态 * \param service_name 被"等待"的服务的话题名称 * \param timeout 等待最大时常,默认为 -1,可以永久等待直至节点关闭 * \return 成功返回 true,否则返回 false。 */ ROSCPP_DECL bool waitForService(const std::string& service_name, ros::Duration timeout = ros::Duration(-1));
1.3 回旋函数
- spinOnce()
/** * \brief 处理一轮回调 * * 一般应用场景: * 在循环体内,处理所有可用的回调函数 * */ ros::spinOnce();
- spin()
/** * \brief 进入循环处理回调 */ ros::spin();
- 二者比较
- 相同点:都用于处理回调函数
- 不同点:ros::spin() 是进入了循环执行回调函数,而 ros::spinOnce() 只会执行一次回调函数(没有循环),在 ros::spin() 后的语句不会执行到,而 ros::spinOnce() 后的语句可以执行
1.4 时间
-
时刻
- 获取时刻,或是设置指定时刻
ros::init(argc,argv,"hello_time"); ros::NodeHandle nh;//必须创建句柄,否则时间没有初始化,导致后续API调用失败 ros::Time right_now = ros::Time::now();//将当前时刻封装成对象 ROS_INFO("当前时刻:%.2f",right_now.toSec());//获取距离 1970年01月01日 00:00:00 的秒数 ROS_INFO("当前时刻:%d",right_now.sec);//获取距离 1970年01月01日 00:00:00 的秒数 ros::Time someTime(100,100000000);// 参数1:秒数 参数2:纳秒 ROS_INFO("时刻:%.2f",someTime.toSec()); //100.10 ros::Time someTime2(100.3);//直接传入 double 类型的秒数 ROS_INFO("时刻:%.2f",someTime2.toSec()); //100.30
- 获取时刻,或是设置指定时刻
-
持续时间
- 设置一个时间区间(间隔)
ROS_INFO("当前时刻:%.2f",ros::Time::now().toSec()); ros::Duration du(10);//持续10秒钟,参数是double类型的,以秒为单位 du.sleep();//按照指定的持续时间休眠 ROS_INFO("持续时间:%.2f",du.toSec());//将持续时间换算成秒 ROS_INFO("当前时刻:%.2f",ros::Time::now().toSec());
- 设置一个时间区间(间隔)
-
持续时间与时刻运算
ROS_INFO("时间运算"); ros::Time now = ros::Time::now(); ros::Duration du1(10); ros::Duration du2(20); ROS_INFO("当前时刻:%.2f",now.toSec()); //1.time 与 duration 运算 ros::Time after_now = now + du1; ros::Time before_now = now - du1; ROS_INFO("当前时刻之后:%.2f",after_now.toSec()); ROS_INFO("当前时刻之前:%.2f",before_now.toSec()); //2.duration 之间相互运算 ros::Duration du3 = du1 + du2; ros::Duration du4 = du1 - du2; ROS_INFO("du3 = %.2f",du3.toSec()); ROS_INFO("du4 = %.2f",du4.toSec()); //PS: time 与 time 不可以运算 // ros::Time nn = now + before_now;//异
-
设置运行频率
ros::Rate rate(1);//指定频率 while (true) { ROS_INFO("-----------code----------"); rate.sleep();//休眠,休眠时间 = 1 / 频率。 }
-
定时器
ros::NodeHandle nh;//必须创建句柄,否则时间没有初始化,导致后续API调用失败 // ROS 定时器 /** * \brief 创建一个定时器,按照指定频率调用回调函数。 * * \param period 时间间隔 * \param callback 回调函数 * \param oneshot 如果设置为 true,只执行一次回调函数,设置为 false,就循环执行。 * \param autostart 如果为true,返回已经启动的定时器,设置为 false,需要手动启动。 */ //Timer createTimer(Duration period, const TimerCallback& callback, bool oneshot = false, // bool autostart = true) const; // ros::Timer timer = nh.createTimer(ros::Duration(0.5),doSomeThing); ros::Timer timer = nh.createTimer(ros::Duration(0.5),doSomeThing,true);//只执行一次 // ros::Timer timer = nh.createTimer(ros::Duration(0.5),doSomeThing,false,false);//需要手动启动 // timer.start(); ros::spin(); //必须 spin
- 定时器的回调函数
void doSomeThing(const ros::TimerEvent &event){ ROS_INFO("-------------"); ROS_INFO("event:%s",std::to_string(event.current_real.toSec()).c_str()); }
- 定时器的回调函数
1.5 其他函数
-
在发布实现时,一般会循环发布消息,循环的判断条件一般由节点状态来控制,C++ 中可以通过 ros::ok() 来判断节点状态是否正常,导致节点退出的原因主要有如下几种
- 节点接收到了关闭信息,比如常用的 ctrl + c 快捷键就是关闭节点的信号
- 同名节点启动,导致现有节点退出
- 程序中的其他部分调用了节点关闭相关的API(C++ 中是 ros::shutdown())
-
另外,日志相关的函数也是极其常用的,在 ROS 中日志被划分成如下级别
- DEBUG (调试):只在调试时使用,此类消息不会输出到控制台
- INFO (信息):标准消息,一般用于说明系统内正在执行的操作
- WARN (警告):提醒一些异常情况,但程序仍然可以执行
- ERROR (错误):提示错误信息,此类错误会影响程序运行
- FATAL (严重错误):此类错误将阻止节点继续运行
2. ROS中的头文件与源文件
2.1 自定义头文件调用
-
需求:设计头文件,可执行文件本身作为源文件
-
流程
-
编写头文件
- 在功能包下的 include/plumbing_head 目录下新建头文件: hello.h
#ifndef _HELLO_H #define _HELLO_H namespace hello_ns { class MyHello { public: void run(); }; } #endif
在 VScode 中,为了后续包含头文件时不抛出异常,需配置 .vscode 下 c_cpp_properties.json 的 includepath 属性
"/home/用户/工作空间/src/功能包/include/**"
-
编写可执行文件(同时也是源文件)
- 在 src 目录下新建文件 hello.cpp
#include "ros/ros.h" #include "plumbing_head/hello.h" namespace hello_ns { void MyHello::run(){ ROS_INFO("自定义头文件的使用...."); } } int main(int argc, char *argv[]) { setlocale(LC_ALL,""); ros::init(argc, argv, "head_node"); hello_ns::MyHello myHello; myHello.run(); return 0; }
-
编辑配置文件并执行
include_directories( include ${catkin_INCLUDE_DIRS} ) add_executable(hello src/hello.cpp) add_dependencies(hello ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(hello ${catkin_LIBRARIES} )
-
2.2 自定义源文件调用
-
需求:设计头文件与源文件,在可执行文件中包含头文件
-
流程
-
编写头文件
- 在功能包下的 include/plumbing_head_src 目录下新建头文件: hello.h
#ifndef _HELLO_H #define _HELLO_H namespace hello_ns{ class MyHello { public: void run(); }; } #endif
在 VScode 中,为了后续包含头文件时不抛出异常,需配置 .vscode 下 c_cpp_properties.json 的 includepath 属性
"/home/用户/工作空间/src/功能包/include/**"
-
编写源文件
- 在 src 目录下新建文件:hello.cpp
#include "plumbing_head_src/hello.h" #include "ros/ros.h" namespace hello_ns{ void MyHello::run(){ ROS_INFO("hello, head and src ..."); } }
-
编写可执行文件
- 在 src 目录下新建文件: use_hello.cpp
#include "ros/ros.h" #include "plumbing_head_src/hello.h" int main(int argc, char *argv[]) { ros::init(argc, argv, "hello_head_src"); hello_ns::MyHello myHello; myHello.run(); return 0; }
-
编辑配置文件并执行
// 头文件与源文件相关配置 include_directories( include ${catkin_INCLUDE_DIRS} ) ## 声明C++库 add_library(head_src include/${PROJECT_NAME}/hello.h src/hello.cpp ) add_dependencies(head_src ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(head_src ${catkin_LIBRARIES} ) // 可执行文件配置 add_executable(use_hello src/use_hello.cpp) add_dependencies(use_hello ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) #此处需要添加之前设置的 head 库 target_link_libraries(use_hello head_src ${catkin_LIBRARIES} )
-