需求:
ROS 内置的乌龟案例并操作,操作过程中使用 rosbag 录制,录制结束后,实现重放
录制:
rosbag record -a -O 目标文件
-a : 所有话题
-o : 设置输出路径
操作小乌龟一段时间,结束录制使用 ctrl + c,在创建的目录中会生成bag文件。
查看:
rosbag info 文件名
回放:
rosbag play 文件名
1.写bag
#include "ros/ros.h"
#include "rosbag/bag.h"
#include "std_msgs/String.h"
/*
需求:使用 rosbag 向磁盘文件写出数据(话题+消息)
流程:
1.导包
2.初始化操作
3.创建rosbag对象
4.打开文件流
5.写数据
6.关闭文件流
*/
int main(int argc, char *argv[])
{
// 2.初始化操作
setlocale(LC_ALL,"");
ros::init(argc,argv,"bag_write");
ros::NodeHandle nh;
//3.创建rosbag对象
rosbag::Bag bag;
//4.打开文件流
bag.open("hello.bag",rosbag::BagMode::Write);
//5.写数据
std_msgs::String msg;
msg.data = "hello xxx";
/*
参数1:话题
参数2:时间戳
参数3.消息
*/
bag.write("/chatter",ros::Time::now(),msg);
bag.write("/chatter",ros::Time::now(),msg);
bag.write("/chatter",ros::Time::now(),msg);
bag.write("/chatter",ros::Time::now(),msg);
//关闭
bag.close();
return 0;
}
#include "ros/ros.h"
#include "rosbag/bag.h"
#include "rosbag/view.h"
#include "std_msgs/String.h"
#include "std_msgs/Int32.h"
/*
需求:使用 rosbag 读取磁盘上的bag文件
流程:
1.导包
2.初始化操作
3.创建rosbag对象
4.打开文件流(以读的方式打开)
5.读数据
6.关闭文件流
*/
int main(int argc, char *argv[])
{
// 2.初始化操作
setlocale(LC_ALL,"");
ros::init(argc,argv,"bag_read");
ros::NodeHandle nh;
//3.创建rosbag对象
rosbag::Bag bag;
//4.打开文件流(以读的方式打开)
bag.open("hello.bag",rosbag::BagMode::Read);
//5.读数据
//取出 话题 时间戳 消息
//可以先获取消息的集合,再迭代取出消息的字段
for (rosbag::MessageInstance const m : rosbag::View(bag))
{
//解析:
std::string topic = m.getTopic();
ros::Time time = m.getTime();
std_msgs::StringPtr p = m.instantiate<std_msgs::String>();
ROS_INFO("解析的内容,话题:%s时间戳:%.2f,消息值:%s",
topic.c_str(),
time.toSec(),
p->data.c_str());
}
//关闭文件流
bag.close();
return 0;
}
1.写bag
#! /usr/bin/env python
import rospy
import rosbag
from std_msgs.msg import String
from Cryptodome.Cipher import AES
"""
需求:写出消息数据到磁盘上的 bag 文件
流程:
1. 导包
2. 初始化
3. 创建 rosbag 对象并且打开文件流
4. 写数据
5. 关闭流
"""
if __name__ == "__main__":
# 1.初始化
rospy.init_node("write_bag_p")
# 3.创建 rosbag 对象并且打开文件流
bag = rosbag.Bag("hello_p.bag",'w')
# 4.写数据
msg = String()
msg.data= "hello bag!"
bag.write("/liaoTian",msg)
bag.write("/liaoTian",msg)
bag.write("/liaoTian",msg)
bag.write("/liaoTian",msg)
bag.write("/liaoTian",msg)
bag.write("/liaoTian",msg)
# 5.关闭流
bag.close()
#! /usr/bin/env python
import rospy
import rosbag
from std_msgs.msg import String
"""
需求:读取磁盘上的 bag 文件
流程:
1. 导包
2. 初始化
3. 创建 rosbag 对象并且打开文件流
4. 读数据
5. 关闭流
"""
if __name__ == "__main__":
# 2. 初始化
rospy.init_node("read_bag_p")
# 3.创建 rosbag 对象并且打开文件流
bag = rosbag.Bag("hello_p.bag",'r')
# 4.读数据
msgs = bag.read_messages("/liaoTian")
for topic,msg,time in msgs:
rospy.loginfo("话题%s,消息%s,时间%s",topic,msg.data,time)
# 5.关闭流
bag.close()
运行(前提:启动roscore):