1 构建自定义数据类型
string name
int32 age
float64 height
#增加自定义消息类型的依赖
find_package(rosidl_default_generators REQUIRED)
# 为接口文件生成源代码
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Student.msg"
)
/*
需求:以固定频率发布文本消息:“hello world!!”,文本后缀编号,每发布一条,编号+1
流程:
1. 包含头文件
2. 初始化ROS2客户端;
3. 自定义节点类;
1. 创建发布方;
2. 创建定时器;
3. 在回调函数中,组织并发布消息,
4. 调用spin函数,传入自定义类的对象指针;
释放资源;
*/
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "base_interfaces_demo/msg/student.hpp"
using namespace std::chrono_literals;
using base_interfaces_demo::msg::Student;
class Talker:public rclcpp::Node
{
private:
/* data */
public:
Talker():rclcpp::Node("talker_node_cpp_stu"),count(0){
RCLCPP_INFO(this->get_logger(),"发布节点已创建!");
// 创建发布者
publisher_=this->create_publisher<Student>("chatter_stu",10);//10为队列长度
// 创建定时器
timer_ = this->create_wall_timer(0.1min,std::bind(&Talker::on_timer,this));
};
private:
rclcpp::Publisher<Student>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
size_t count;
void on_timer(){
auto message_= Student();
message_.name="Pang Weijian";
message_.age=35;
message_.height=175.7;
RCLCPP_INFO(this->get_logger(),"发布方发布的消息:姓名:%s,年龄:%d, 身高:%f",message_.name.c_str(),message_.age,message_.height);
publisher_->publish(message_);
}
//~Talker():rclcpp::Node();
};
int main(int argc, char ** argv)
{
//初始化客户端
rclcpp::init(argc,argv);
//
// 调用回旋函数
rclcpp::spin(std::make_shared<Talker>());
// 释放资源
rclcpp::shutdown();
//printf("hello world cpp01_topic package\n");
return 0;
}
3、订阅方实现
/*
需求:订阅发布方发布的消息并在终端输出
流程:
1.包含头文件;
2.初始化客户端;
3.自定义节点类;
1. 创建订阅方;
2. 在回调函数中解析并输出数据;
4.调用回旋函数,并传入节点对象指针;
5.资源释放
*/
#include "rclcpp/rclcpp.hpp"
//#include "std_msgs/msg/string.hpp"
#include "base_interfaces_demo/msg/student.hpp"
using base_interfaces_demo::msg::Student;
// 自定义节点类
class Listener:public rclcpp::Node
{
private:
/* data */
void do_cb(const Student &msg){
RCLCPP_INFO(this->get_logger(),"订阅到的消息:姓名:%s,年龄:%d,身高:%f",msg.name.c_str(),msg.age,msg.height);
}
rclcpp::Subscription<Student>::SharedPtr subscription_;
public:
Listener();
~Listener();
};
Listener::Listener():Node("listener_node_cpp")
{
RCLCPP_INFO(this->get_logger(),"订阅方创建");
subscription_ = this->create_subscription<Student>("chatter_stu",10,std::bind(&Listener::do_cb,this,std::placeholders::_1));
}
Listener::~Listener()
{
}
int main(int argc, char const *argv[]){
// 初始化节点
rclcpp::init(argc,argv);
// 调用回旋函数
rclcpp::spin(std::make_shared<Listener>());
return 0;
}
4. 运行colcon build 编译所选包,运行结果如下: