【ROS2】话题通信
话题通信
※作用:方便各类传感器和执行器数据在机器人系统中传递
ROS2话题机制
发布者
订阅者
话题名称
话题类型:消息接口


示例
//查看节点详细信息
ros2 node info /turtlesim
/turtlesim
Subscribers://
/parameter_events: rcl_interfaces/msg/ParameterEvent
/turtle1/cmd_vel: geometry_msgs/msg/Twist
Publishers:
/parameter_events: rcl_interfaces/msg/ParameterEvent
/rosout: rcl_interfaces/msg/Log
/turtle1/color_sensor: turtlesim/msg/Color
/turtle1/pose: turtlesim/msg/Pose
【话题名称】 【消息接口】
...
ros2 topic echo:输出话题数据
//订阅/turtle1/pose 实时输出位姿
ros2 topic echo /turtle1/pose
---
x: 5.544444561004639
y: 5.544444561004639
theta: 0.0
linear_velocity: 0.0
angular_velocity: 0.0
---
//查看话题具体信息
ros2 topic info /turtle1/cmd_vel -v
Type(消息接口): geometry_msgs/msg/Twist
Publisher count: 0
Subscription count: 1
Node name: turtlesim
Node namespace: /
Topic type: geometry_msgs/msg/Twist
Endpoint type: SUBSCRIPTION
GID: 01.0f.e9.4f.81.0b.0f.1f.00.00.00.00.00.00.1b.04.00.00.00.00.00.00.00.00
QoS profile:
Reliability: RELIABLE
History (Depth): UNKNOWN
Durability: VOLATILE
Lifespan: Infinite
Deadline: Infinite
Liveliness: AUTOMATIC
Liveliness lease duration: Infinite
ros2 interface show:输出接口的定义内容
ros2 interface show geometry_msgs/msg/Twist
# This expresses velocity in free space broken into its linear and angular parts.
Vector3 linear
float64 x
float64 y
float64 z
Vector3 angular
float64 x
float64 y
float64 z
了解消息接口具体内容->进行发布
ros2 topic pub /turtle1/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 1.0}}"
※大括号用于区分消息结构层级,冒号后需要添加空格用于区分
利用C++进行话题订阅和发布
发布速度:publisher
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include <chrono>
using namespace std::chrono_literals;//使用时间单位字面量->用s和ms表示时间
class TurtleCircle : public rclcpp::Node{
private:
//定时器智能指针
rclcpp::TimerBase::SharedPtr timer_;
//发布者智能指针
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
public:
explicit TurtleCircle(const std::string& node_name) : Node(node_name)
{
//调用父类函数->创建订阅者
//<>:C++模版语法 设置话题消息接口
publisher_=this->create_publisher<geometry_msgs::msg::Twist>("/turtle1/cmd_vel",10);//与海龟订阅的话题名称保持一致
//10暂时不用管
//创建定时器
timer_=this->create_wall_timer(1000ms,std::bind(&TurtleCircle::timer_callback,this));
//bind作用:将成员方法timer_callback变成可以直接调用的回调函数
}
private:
void timer_callback(){
auto msg=geometry_msgs::msg::Twist();//构造函数 对象
msg.linear.x=1.0;
msg.angular.z=0.5;
publisher_->publish(msg);//发布信息
}
};
int main(int argc,char *argv[]){
rclcpp::init(argc,argv);
auto node=std::make_shared<TurtleCircle>("vw50");
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
订阅pose实现闭环控制:subscribe
发布速度控制命令到话题"/turtle1/cmd_vel"->控制海龟移动
订阅"turtle1/pose"->获取海龟实时位置
#include"geometry_msgs/msg/twist.hpp"
#include"rclcpp/rclcpp.hpp"
#include"turtlesim/msg/pose.hpp"
class TurtleController : public rclcpp::Node{
public:
TurtleController() : Node("turtle_controller"){
velocity_publisher_ = this->create_publisher<geometry_msgs::msg::Twist>
("/turtle1/cmd_vel",10);
pose_subscription_ = this->create_subscription<turtlesim::msg::Pose>("turtle1/pose",10,
std::bind(&TurtleController::on_pose_received_,this,std::placeholders::_1));
//当后台收到数据时,调用该回调函数处理
}
private:
//收到位置计算误差,发布速度指令
void on_pose_received_(const turtlesim::msg::Pose::SharedPtr pose){
auto message = geometry_msgs::msg::Twist();
//1.记录当前位置
double current_x = pose->x;
double current_y = pose->y;
RCLCPP_INFO(this->get_logger(),"当前位置:(x=%f,y=%f)",current_x,current_y);
//2.计算与目标之间的距离,以及与当前海龟朝向的角度差
double distance = std::sqrt((target_x_-current_x)*(target_x_-current_x)
+(target_y_-current_y)*(target_y_-current_y));
//atan2:y/x的反正切值
//与std::atan()函数不同,std::atan2()考虑x和y的符号,可正确确定角度所在的象限
//计算目标点位置相对当前位置的角度,将结果和当前朝向作差
double angle = std::atan2(target_y_-current_y,target_x_-current_x) - pose -> theta;
//3.控制策略:距离大于0.1继续运动,角度差大于0.2原地旋转,否则直行
if(distance > 0.1){
//计算角速度
if(fabs(angle)>0.2){
message.angular.z=fabs(angle);
}
else{
//通过比例控制器计算输出速度
message.linear.x=k_*distance;
}
}
//4.限制最大值并发布消息
if(message.linear.x>max_speed_){
message.linear.x=max_speed_;
}
velocity_publisher_->publish(message);//发布消息
}
private:
// 订阅/turtle1/pose获取海龟实时位置
rclcpp::Subscription<turtlesim::msg::Pose>::SharedPtr pose_subscription_;
//话题发布者
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr velocity_publisher_;
/*目标点*/
double target_x_{1.0}; //目标位置x 默认值1.0
double target_y_{1.0}; //目标位置y 默认值1.0
double k_{1.0}; //比例系数,控制输出=误差x比例系数
double max_speed_{3.0}; //最大线速度 默认值3.0
};
int main(int argc,char** argv){
rclcpp::init(argc,argv);
auto node=std::make_shared<TurtleController>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
自定义通信接口
※cmake版本不要太高!
构建消息接口功能包
ros2 pkg create status_interfaces
--build-type ament_cmake
--dependencies rosidl_default_generators builtin_interfaces
--license Apache-2.0
【依赖】
builtin_interfaces:使用其时间接口Time -> 表示记录信息的时间
rosidl_default_generators -> 将自定义消息文件转换为C++、Python源码
定义话题消息文件:功能包的msg目录
文件名必须以大写字母开头,并且只能由大小写字母和数字构成
消息接口定义文件 SystemStatus.msg
builtin_interfaces/Time stamp # 记录时间戳
string host_name # 系统名称
float32 cpu_percent # CPU使用率
float32 memory_percent # 内存使用率
float32 memory_total # 内存总量
float32 memory_available # 剩余有效内存
float64 net_sent # 网络发送数据总量
float64 net_recv # 网络接受数据总量
CMakeList.txt注册消息接口:在对应功能包的Cmake
【在package依赖后】
在rosidl_generate_interfaces中添加builtin_interfaces依赖
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/SystemStatus.msg"
DEPENDENCIES builtin_interfaces
)
在清单文件package.xml中添加声明
声明该功能包是一个消息接口功能包
<license>Apache-2.0</license>
# 加这一句
<member_of_group>rosidl_interface_packages</member_of_group>
<buildtool_depend>ament_cmake</buildtool_depend>
->构建消息接口功能包
source install/setup.bash # 同样要使用source告诉ROS2功能包的安装位置
ros2 interface show status_interfaces/msg/SystemStatus

浙公网安备 33010602011771号