一、命令行
1、录制bag
rosbag record -h # 查看record使用方法
rosbag record -a # 录制所有的topic,将bag文件保存在当前文件夹下,并以录制结束时间(日期加时间)命名
rosbag record /topic1 /topic2 # 录制指定的topic
rosbag record -O <bag_name>.bag /topic # (大写o)指定生成数据包的名字
rosbag record -o <bag_prefix> /topic # (小写o)给数据包的名字加前缀,包名为<bag_prefix>+时间戳.bag
rosbag record -b # buffsize(MB),Default: 256, 0 = infinite
You could run your rosbag with a Not anonymous node name:
$ rosbag record -o /file/name /topic __name:=my_bag
and then kill it via rosnode kill:
$ rosnode kill /my_bag
This assures that rosbag stops gracefully.
2、回放bag
rosbag play <bag_name> # Hit space to toggle paused, or 's' to step.
rosbag play bag1 bag2 # 回放多个bag
rosbag play <bag_name> --topics /topic1 /topic2 # 回放指定话题
rosbag play <bag_name> /image_raw:=/camera/image_raw # 话题名重映射,将/image_raw映射到/camera/image_raw。另一种方法是在roslaunch中修改,<remap from="/image_raw" to="/camera/image_raw"/>
rosbag play -l <bag_name> # 循环播放
rosbag play -r 0.5 <bag_name> # 以0.5倍的录制频率回放
rosbag play --clock --hz=200 <bag_name> # 指定回放频率,默认100hz
rosbag play <bag_name> -d <delay_time> # 等待一定时间之后发布bag文件中的内容
rosbag play -s 10 <bag_name> # 跳过前面10s,从第10s开始播放
rosbag play --skip-empty=1.0 <bag_name> # 每当遇到超过1秒的间隙时,它会立即及时跳跃
rosbag play --pause <bag_name> # 开始播放立刻暂停,按空格键可以恢复/暂停播放。如果在启动rosbag play之后还有一些其他设置要做,比如在rviz中配置可视化选项等,如果不播放rosbag,而是先设置rviz选项,可能有些topic还没有生成,设置的时候没有办法选择,ros graph里面也不存在对应的topic;如果先播放 rosbag,然后再做其他设置,则可能错过了rosbag最开始的一部分信息。解决方案是在播放rosbag时选择“暂停”功能,这样既可以得到相应的topic,又避免错过开头的信息。
使用仿真时间
rosparam set use_sim_time true
rosbag play <bag_name> --clock
3、消息过滤
rosbag filter src.bag dst.bag "topic == '/foo' or topic == '/bar'" # 根据话题名过滤
rosbag filter src.bag dst.bag "t.to_sec() >= 1573631118.88 and t.to_sec() <= 1573631309.16" # 根据时间戳范围过滤
rosbag filter src.bag dst.bag "topic != 'tf' or ((len(m.transforms) > 0 and m.transforms[0].header.frame_id != 'odom') and (len(m.transforms) <= 1 or (len(m.transforms) > 1 and m.transforms[1].header.frame_id != 'odom')) and (len(m.transforms) <= 2 or (len(m.transforms) > 2 and m.transforms[2].header.frame_id != 'odom')) and (len(m.transforms) <= 3 or (len(m.transforms) > 3 and m.transforms[3].header.frame_id != 'odom')) and (len(m.transforms) <= 4 or (len(m.transforms) > 4 and m.transforms[4].header.frame_id != 'odom')))"
4、查看bag的基本信息
rosbag info -h
rosbag info -y <bag_name> # 输出yaml格式的信息
rosbag info <bag_name> # 显示bag信息(开始和结束时间,包含的话题名称及其类型,消息数量、频率以及压缩统计信息)
rosbag info -y -k duration <bag_name> # 输出bag中指定域的信息,比如只显示持续时间
5、其他相关
# 检查一个bag在当前的系统中是否可以回放
rosbag check <bag_name>
# 如果录制的bag很大,可以进行压缩,默认压缩格式为bz2
rosbag compress <bag_name>
# 手动指定压缩格式为bz2
rosbag compress -j <bag_name>
# 指定压缩格式为LZ4(BZ2比LZ4更小但也更慢)
rosbag compress --lz4 <bag_name>
# 压缩完后需要解压缩
rosbag decompress <bag_name>
# 如果回放遇到问题,提示reindex的话,执行后会自动生成一个原bag的备份
rosbag reindex <bag_name>
# topic重命名
rosrun rosbag topic_renamer.py <in_topic> <in_bag> <out_topic> <out_bag>
# 输出bag中指定topic内容
rostopic echo -b bag_name.bag -p /topic_name
# 压缩图片转化为正常图片消息发布,压缩的图像topic: /camera_obj_center/image_color/compressed
rosrun image_transport republish compressed in:=/camera_obj_center/image_color raw out:=/camera/image_raw
# 使用image_view(或rviz)查看视频流效果
rosrun image_view image_view image:=/image_topic
# 查看压缩视频流:
rosrun image_view image_view image:=/image_basic_topic _image_transport:=compressed
二、C++
1、图像序列生成bag
#include <ros/ros.h>
#include <rosbag/bag.h>
#include <opencv2/highgui/highgui.hpp>
#include "cv_bridge/cv_bridge.h" // opencv图像格式转化为ROS图像格式
int main(int argc, char **argv)
{
ros::init(argc, argv, "rosbag_recode_node");
ros::NodeHandle nh;
rosbag::Bag bag;
bag.open("/home/alan/Desktop/alan_test.bag", rosbag::bagmode::Write);
// bag.open("/home/alan/Desktop/alan_test.bag", rosbag::bagmode::Append);
// bag.setCompression(rosbag::compression::LZ4);
cv::VideoCapture cap(0);
while (ros::ok() && (cv::waitKey(1) != 27)) { // 按Esc退出
cv::Mat frame;
cap >> frame;
if (frame.empty()) {
std::cout << "error, no image" << std::endl;
return -1;
}
cv::imshow("image", frame);
cv::waitKey(10);
std_msgs::Header header;
header.frame_id = "image_frame"; // 设置坐标系,多传感器、RVIZ显示时会用到
header.stamp = ros::Time::now();
sensor_msgs::ImagePtr image_msg = cv_bridge::CvImage(header, "bgr8", frame).toImageMsg();
sensor_msgs::CompressedImagePtr compressed_image_msg = cv_bridge::CvImage(header, "bgr8", frame).toCompressedImageMsg();
bag.write("image_raw", ros::Time::now(), image_msg); // 当前时间
bag.write("image_raw/compressed", ros::Time::now(), compressed_image_msg);
//ros::Time time;
//time.fromNSec(timestamp); // 从图像数据集生成bag时,timestamp一般为图像名
//bag.write("image_topic", time, msg);
}
bag.close();
cap.release();
return 0;
}
CMakeLists.txt:
cmake_minimum_required(VERSION 2.8.3)
project(alan_package)
set(CMAKE_CXX_STANDARD 11)
find_package(OpenCV REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})
find_package(catkin REQUIRED COMPONENTS
roscpp
rosbag
cv_bridge
)
include_directories(
${catkin_INCLUDE_DIRS}
)
add_executable(create_image_bag src/create_image_bag.cpp)
target_link_libraries(create_image_bag
${catkin_LIBRARIES}
${OpenCV_LIBS})
说明:
CvBridge中常用的编码:
mono8: CV_8UC1, grayscale image
mono16: CV_16UC1, 16-bit grayscale image
bgr8: CV_8UC3, color image with blue-green-red color order
rgb8: CV_8UC3, color image with red-green-blue color order
bgra8: CV_8UC4, BGR color image with an alpha channel
rgba8: CV_8UC4, RGB color image with an alpha channel
2、从bag中保存图像
#include <string>
#include <rosbag/bag.h>
#include <rosbag/view.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CompressedImage.h>
#include <opencv2/opencv.hpp>
// #include <cv_bridge/cv_bridge.h>
// #include "sensor_msgs/image_encodings.h"
int main(int argc, char* argv[]) {
std::string image_raw_topic = "/image_raw";
std::string image_raw_compressed_topic = "/image_raw/compressed";
std::vector<std::string> bag_topics;
bag_topics.push_back(image_raw_topic);
bag_topics.push_back(image_raw_compressed_topic);
rosbag::Bag bag;
bag.open("/home/alan/Desktop/alan_test.bag", rosbag::bagmode::Read);
rosbag::View view(bag, rosbag::TopicQuery(bag_topics));
// std::vector<std::string> types;
// types.push_back(std::string("geometry_msgs/TransformStamped"));
// rosbag::View view(bag, rosbag::TypeQuery(types));
// sensor_msgs::CompressedImageConstPtr image_message = view.begin()->instantiate<sensor_msgs::CompressedImage>();
for (const rosbag::MessageInstance& message_instance : view) {
if (message_instance.getTopic() == image_raw_compressed_topic) {
auto image_message = // sensor_msgs::CompressedImageConstPtr
message_instance.instantiate<sensor_msgs::CompressedImage>();
long long timestamp = image_message->header.stamp.toNSec();
// convert compressed image data to cv::Mat
cv::Mat3b color_image =
cv::imdecode(cv::Mat(image_message->data), cv::IMREAD_COLOR);
// cv_bridge::CvImagePtr cv_ptr;
// cv_ptr = cv_bridge::toCvCopy(image_message, sensor_msgs::image_encodings::BGR8);
// cv::Mat color_image = cv_ptr->image;
cv::imwrite("/home/alan/Desktop/image_raw/compressed/" + std::to_string(timestamp) + ".jpg", color_image);
cv::waitKey(30);
} else if (message_instance.getTopic() == image_raw_topic) {
auto image_message =
message_instance.instantiate<sensor_msgs::CompressedImage>();
long long timestamp = image_message->header.stamp.toNSec();
cv::Mat3b color_image = cv::Mat(image_message->data);
cv::imwrite("/home/alan/Desktop/image_raw/" + std::to_string(timestamp) + ".jpg", color_image);
cv::waitKey(30);
}
}
}
解析pose
#include <geometry_msgs/PoseStamped.h>
else if (message_instance.getTopic() == config_.pose_topic()) {
auto pose_message =
message_instance.instantiate<geometry_msgs::PoseStamped>();
ProcessPoseMessage(pose_message)
void ProcessPoseMessage(
const geometry_msgs::PoseStamped::ConstPtr &pose_msg) {
double timestamp = pose_msg->header.stamp.toSec();
// double timestamp = pose_msg->header.stamp.sec + static_cast<double>(pose_msg->header.stamp.nsec) * 1e-9;
// long long timestamp = pose_msg->header.stamp.toNSec();
Eigen::Quaterniond orientation(pose_msg->pose.orientation.w,
pose_msg->pose.orientation.x,
pose_msg->pose.orientation.y,
pose_msg->pose.orientation.z);
Eigen::Vector3d position(pose_msg->pose.position.x,
pose_msg->pose.position.y,
pose_msg->pose.position.z);
}
3、topic重命名
main.cc:
#include <string>
#include <rosbag/bag.h>
#include <rosbag/view.h>
int main(int argc, char **argv) {
std::string old_topic = "/old_topic_name";
std::string new_topic = "/new_topic_name";
std::string old_bag = "old.bag";
std::string new_bag = "new.bag";
rosbag::Bag bag_read;
rosbag::Bag bag_write;
bag_read.open(old_bag, rosbag::bagmode::Read);
bag_write.open(new_bag, rosbag::bagmode::Write);
rosbag::View view_all(bag_read);
for(const rosbag::MessageInstance& m : view_all) {
if (m.getTopic() == old_topic) {
bag_write.write(new_topic, m.getTime(), m);
} else {
bag_write.write(m.getTopic(), m.getTime(), m);
}
}
bag_read.close();
bag_write.close();
return 0;
}
CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(topic_rename)
set(CMAKE_CXX_STANDARD 11)
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
find_package(catkin REQUIRED COMPONENTS
roscpp
rosbag
)
include_directories(
${catkin_INCLUDE_DIRS}
)
add_executable(topic_rename main.cc)
target_link_libraries(topic_rename
${catkin_LIBRARIES})
4、将一个bag中的topic内容加入到另一个bag中
(待改进:加入topic所有消息、写成模版、rosbag相似的命令行?)
#include <gflags/gflags.h>
#include <glog/logging.h>
#include <ros/ros.h>
#include <rosbag/bag.h>
#include <rosbag/view.h>
#include <std_msgs/String.h>
DEFINE_string(topic_name, "/foo/bar", "topic_name");
DEFINE_string(bag_path_in, "1.bag", "bag contain topic");
DEFINE_string(bag_path_out, "2.bag", "bag does not contain topic");
int main(int argc, char **argv)
{
ros::init(argc, argv, "rosbag_add_topic");
ros::NodeHandle nh;
rosbag::Bag bag_in;
bag_in.open(FLAGS_bag_path_in.c_str(), rosbag::bagmode::Read);
rosbag::View view_in(bag_in, rosbag::TopicQuery(FLAGS_topic_name));
if (view_in.size() == 0) {
LOG(FATAL) << FLAGS_bag_path_in << " does not contain topic: " << FLAGS_topic_name;
}
rosbag::Bag bag_out;
bag_out.open(FLAGS_bag_path_out.c_str(), rosbag::bagmode::Append);
std_msgs::String string_message = *(view_in.begin()->instantiate<std_msgs::String>());
// std_msgs::String string_message;
// string_message.data = std::string("foo");
bag_out.write(FLAGS_topic_name, view_in.getBeginTime(), string_message);
bag_in.close();
bag_out.close();
return 0;
}
三、Python
1、topic重命名
#!/usr/bin/env python3
import os
import argparse
import logging
import rosbag
def run():
logging.basicConfig(format='%(levelname)s: %(message)s', level=logging.INFO)
parser = argparse.ArgumentParser(description='......')
parser.add_argument('-old_topic', default='/old_topic_name')
parser.add_argument('-new_topic', default='/new_topic_name')
parser.add_argument('-b', dest='bag', required=True)
parser.add_argument('-o', dest='output_bag', default='')
args = parser.parse_args()
output_bag = args.output_bag
if not output_bag or output_bag == args.bag:
strs=os.path.splitext(args.bag)
output_bag = strs[0] + '_' + strs[-1]
bag_read = rosbag.Bag(args.bag)
bag_write = rosbag.Bag(output_bag, mode='w')
for topic, msg, t in bag_read.read_messages(): # 指定topic bag_read.read_messages(topics=['/foo', '/bar'])
# time = t.to_sec()
# x = msg.pose.position.x
if topic == args.old_topic:
bag_write.write(args.new_topic, msg, t)
else:
bag_write.write(topic, msg, t)
bag_read.close()
bag_write.close()
logging.info("Done!\ntopic rename: %s --> %s\noutput bag: %s" % (args.old_topic, args.new_topic, output_bag))
if __name__ == '__main__':
run()
参考:
http://wiki.ros.org/rosbag/Commandline
http://wiki.ros.org/cv_bridge/Tutorials/UsingCvBridgeToConvertBetweenROSImagesAndOpenCVImages
rosbag::Bag bag;
bag.open("/tmp/test.bag", rosbag::bagmode::Write);
void PoseCallback(const ros::MessageEvent<const geometry_msgs::PoseStamped> &event) {
bag.write("/pose_topic", event.getReceiptTime(), event.getMessage());
}
int main(int argc, char **argv) {
ros::init(argc, argv, "record_node");
ros::NodeHandle nh("~");
ros::Subscriber pose_sub_ = nh.subscribe("/pose_topic", 1, &PoseCallback);
ros::spin();
}