ROS学习笔记四:Using C++ Classes in ROS
为了提高ROS代码的可复用性和产出,有效的使用classes就很有必要了。
总的来说,主要做两件事:
在一个头文件中定义一个class
- 定义这个class中的所有成员函数的原型
- 定义private和public数据成员
- 定义class的构造函数原型
写一个单独的执行程序
- include上述的头文件
- 包含各个成员函数的执行代码
- 在构造函数中有相应代码去封装必要的初始化
一.在头文件中定义一个类(class)
以下是一个在头文件中定义一个类的例子,以“example_ros_class.h”命名:
#ifndef EXAMPLE_ROS_CLASS_H_ //①---一种技巧,注释请看最后一行代码
#define EXAMPLE_ROS_CLASS_H_ //②---一种技巧,注释请看最后一行代码
//常用的成员
#include <math.h>
#include <stdlib.h>
#include <string>
#include <vector>
#include <ros/ros.h> //惯例添加
//需要用到的消息类型,有.msg和.srv两类,要用到两种通信机制
#include <std_msgs/Bool.h>
#include <std_msgs/Float32.h>
#include <std_srvs/Trigger.h> // 可以用rossrv show std_srvs/Trigger查看消息类型
// 现在开始定义一个类,包括构造函数,成员函数和成员变量
//构造函数是在类里面使用的函数,构造函数的名称与类额名称相同
class ExampleRosClass
{
public:
ExampleRosClass(ros::NodeHandle* nodehandle); //main函数需要一个ROS的节点句柄,并通过这个节点句柄连接到这个构造函数
private:
// 私有的数据成员只能在该类中被调用
ros::NodeHandle nh_; // 通过这个节点句柄连接main函数和构造函数
//定义一些subscriber、publisher和service的变量
ros::Subscriber minimal_subscriber_; //这里三个变量后面都加了下划线,作用是提醒这三个变量只能在该类(ExampleRosClass)中被调用
ros::ServiceServer minimal_service_;
ros::Publisher minimal_publisher_;
double val_from_subscriber_; //定义变量接收subscriber回调函数的变量,有优于使用全局变量,便于将数据从subscriber处传到其他成员函数
double val_to_remember_; // 储存变量数据
//-------------------------------------------------------
void initializeSubscribers();
void initializePublishers();
void initializeServices();
void subscriberCallback(const std_msgs::Float32& message_holder); //subscriber回调函数的原型
bool serviceCallback(std_srvs::TriggerRequest& request, std_srvs::TriggerResponse& response);//service回调函数的原型
//-------------------------------------------------------
//以上分割线内的五个函数,尽量避免将执行代码写入函数中,应将对应的执行代码写入另外的独立的一个或多个 .cpp 文件中
}; // 注意,类定义的结尾处除了要加大括号还要记得加上一个分号
#endif // ③这一行与头文件开头的两行“#ifndef”和“#define”是一种技巧,主要用于防止重复定义宏和重复包含头文件
二.写一个单独的执行程序
以下是一个单独的执行程序的例子,文件名为“example_ros_class.cpp” :
#include "example_ros_class.h" //我们自定义类(class)的头文件
// 不得不通过节点句柄指针进入构造函数再有构造函数去构建subscriber
ExampleRosClass::ExampleRosClass(ros::NodeHandle* nodehandle):nh_(*nodehandle) // 构造函数
{
ROS_INFO("in class constructor of ExampleRosClass");
initializeSubscribers(); // 需要通过成员协助函数帮助构建subscriber,在构造函数中做初始化的工作
initializePublishers();
initializeServices();
val_to_remember_=0.0; //初始化储存数据的变量的值
}
//以下是一个成员协助函数,帮助构建subscriber
void ExampleRosClass::initializeSubscribers()
{
ROS_INFO("Initializing Subscribers");
minimal_subscriber_ = nh_.subscribe("example_class_input_topic", 1, &ExampleRosClass::subscriberCallback,this);
//订阅了名称为"example_class_input_topic"的topic
//&ExampleRosClass::subscriberCallback 是一个指向成员函数“ExampleRosClass”的指针
// “this”的用意是指向当前实例(ExampleRosClass)
}
//与上相同
void ExampleRosClass::initializeServices()
{
ROS_INFO("Initializing Services");
minimal_service_ = nh_.advertiseService("example_minimal_service",
&ExampleRosClass::serviceCallback,
this);
}
//与上相同
void ExampleRosClass::initializePublishers()
{
ROS_INFO("Initializing Publishers");
minimal_publisher_ = nh_.advertise<std_msgs::Float32>("example_class_output_topic", 1, true);
}
//以下内容与之前在构建publishers/subscribers通信时,编写的publishers和subscribers节点相似
//大部分的工作都是在回调函数中完成的
void ExampleRosClass::subscriberCallback(const std_msgs::Float32& message_holder) {
val_from_subscriber_ = message_holder.data; // 用成员变量储存回调的数据
ROS_INFO("myCallback activated: received value %f",val_from_subscriber_);
std_msgs::Float32 output_msg;
val_to_remember_ += val_from_subscriber_; //储存每次调用的数据
output_msg.data= val_to_remember_;
minimal_publisher_.publish(output_msg); //在这里之所以可以使用publishers的功能,是因为在类中publishers也是其他一个成员函数,所以可以被调用
}
//与构建services/clients通信时相似
bool ExampleRosClass::serviceCallback(std_srvs::TriggerRequest& request, std_srvs::TriggerResponse& response) {
ROS_INFO("service callback activated");
response.success = true; // Trigger的消息类型是bool和string,对应的数据类型就是success和message
response.message = "here is a response string";
return true;
}
int main(int argc, char** argv)
{
// ROS set-ups:
ros::init(argc, argv, "exampleRosClass"); //节点名
ros::NodeHandle nh; // 必须在main函数中创建一个节点句柄给构造函数使用,并且需要把它传递到构造函数中
ROS_INFO("main: instantiating an object of type ExampleRosClass");
ExampleRosClass exampleRosClass(&nh); //实例化一个ExampleRosClass对象并将指针传递给nodehandle以供构造函数使用
ROS_INFO("main: going into spin; let the callbacks do all the work");
ros::spin();
return 0;
}
惯例还要建立package.xml和CMakeLists.txt文档,内容与头两种通信机制相似。
至此搭建就完成了,进行编译测试
catkin_make
在一个terminal中运行(已运行roscore的情况)
rosrun example_ros_class example_ros_class
输出
[ INFO] [1521039612.137001085]: main: instantiating an object of type ExampleRosClass
[ INFO] [1521039612.137140031]: in class constructor of ExampleRosClass
[ INFO] [1521039612.137185560]: Initializing Subscribers
[ INFO] [1521039612.151026356]: Initializing Publishers
[ INFO] [1521039612.155953280]: Initializing Services
[ INFO] [1521039612.157199947]: main: going into spin; let the callbacks do all the work
接下来测试以下service通信成不成功,在另一个terminal中运行
rosservice call example_minimal_service
看是否有如下输出
success: True
message: here is a response string
再测试subscriber是否接收到订阅的信息,在另一个terminal中运行
rostopic pub -r 2 example_class_input_topic std_msgs/Float32 2.0
看是否有如下输出
[ INFO] [1521039709.313823852]: service callback activated
[ INFO] [1521039846.928363663]: myCallback activated: received value 2.000000
[ INFO] [1521039847.428383242]: myCallback activated: received value 2.000000
[ INFO] [1521039847.928050343]: myCallback activated: received value 2.000000
[ INFO] [1521039848.428328990]: myCallback activated: received value 2.000000
[ INFO] [1521039848.928533710]: myCallback activated: received value 2.000000
以上就是一个类的简单运用的例子。