Rosbag Format Conversion

Using Rosbag data on BasicAI Cloud Platform

What is Rosbag?

Rosbag or bag is a file format used in ROS for storing ROS message data. These bags are typically created by subscribing to one or more ROS topics and storing the received message data in an efficient file structure. On the BasicAI Cloud platform, these formatted rosbag files can be read, assisting in filtering and extracting message data. The following sections provide a detailed overview of rosbag formats and the workflow for extracting data from them.

::: warningYou must work on a server where ROS and related dependencies are installed.
:::To view the bag file information, enter the command in the path where the bag package is located:

$ rosbag info bagsname.bag #bag file name

Topics record the topics contained in the bag file, the corresponding types, and how many frame files there are. As shown in the figure, the file contains 133 frames of image data and 142 frames of point cloud data.

Open a terminal and run roscore:

Input the command:

$ roscore

After Roscore starts running =======> Create a new terminal and start parsing point clouds and images.

Parse .pcd (point cloud file)

Pointcloud2 Type Point Cloud Data

Run the command in the bag directly:
$ rosrun pcl_ros bag_to_pcd bagsname.bag /radars_concat_node/fusion_radar pcd

bagsname.bag ————bag name
/radars_concat_node/fusion_radar ————topic node name
pcd ————Folder name to save .pcd files

After successful operation, you can view the parsed .pcd file in the pcd folder.

CustomMsg Type point Cloud Data

  1. Create ros function package
cd livox_repub/src
catkin_init_workspace 
cd ..
catkin_make
  1. Write resource files
mkdir livox_repub
cd livox_repub
vi package.xml
<package>
  <name>livox_repub</name>
  <version>0.0.0</version>

  <description>
    This is a .
  </description>

  <maintainer email="[email protected]">xxx</maintainer>

  <license>BSD</license>

  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>geometry_msgs</build_depend>
  <build_depend>nav_msgs</build_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>rospy</build_depend>
  <build_depend>std_msgs</build_depend>
  <build_depend>sensor_msgs</build_depend>
  <build_depend>tf</build_depend>
  <build_depend>pcl_ros</build_depend>
  <build_depend>livox_ros_driver</build_depend>

  <run_depend>geometry_msgs</run_depend>
  <run_depend>nav_msgs</run_depend>
  <run_depend>sensor_msgs</run_depend>
  <run_depend>roscpp</run_depend>
  <run_depend>rospy</run_depend>
  <run_depend>std_msgs</run_depend>
  <run_depend>tf</run_depend>
  <run_depend>pcl_ros</run_depend>
  <run_depend>livox_ros_driver</run_depend>

  <test_depend>rostest</test_depend>
  <test_depend>rosbag</test_depend>

  <export>
  </export>
</package>

vi CMakeLists.txt

cmake_minimum_required(VERSION 2.8.3)
project(livox_repub)

SET(CMAKE_BUILD_TYPE "Debug")


set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fexceptions")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -pthread -std=c++0x -std=c++14 -fexceptions -Wno-unused-local-typedefs")

find_package(OpenMP QUIET)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS}   ${OpenMP_C_FLAGS}")

find_package(catkin REQUIRED COMPONENTS
  geometry_msgs
  nav_msgs
  sensor_msgs
  roscpp
  rospy
  std_msgs
  pcl_ros
  tf
  livox_ros_driver
  )

find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
find_package(OpenCV REQUIRED)

include_directories(
        ${catkin_INCLUDE_DIRS} 
        ${EIGEN3_INCLUDE_DIR}
        ${PCL_INCLUDE_DIRS})

catkin_package(
  CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs
  DEPENDS EIGEN3 PCL OpenCV
  
)

add_executable(livox_repub livox_repub.cpp)
target_link_libraries(livox_repub ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS})

vi livox_repub.cpp

#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/PointCloud2.h>
#include "livox_ros_driver/CustomMsg.h"

typedef pcl::PointXYZINormal PointType;
typedef pcl::PointCloud<PointType> PointCloudXYZI;

ros::Publisher pub_pcl_out0, pub_pcl_out1;
uint64_t TO_MERGE_CNT = 1; 
constexpr bool b_dbg_line = false;
std::vector<livox_ros_driver::CustomMsgConstPtr> livox_data;
void LivoxMsgCbk1(const livox_ros_driver::CustomMsgConstPtr& livox_msg_in) {
  livox_data.push_back(livox_msg_in);
  if (livox_data.size() < TO_MERGE_CNT) return;

  pcl::PointCloud<PointType> pcl_in;

  for (size_t j = 0; j < livox_data.size(); j++) {
    auto& livox_msg = livox_data[j];
    auto time_end = livox_msg->points.back().offset_time;
    for (unsigned int i = 0; i < livox_msg->point_num; ++i) {
      PointType pt;
      pt.x = livox_msg->points[i].x;
      pt.y = livox_msg->points[i].y;
      pt.z = livox_msg->points[i].z;
      float s = livox_msg->points[i].offset_time / (float)time_end;

      pt.intensity = livox_msg->points[i].line +livox_msg->points[i].reflectivity /10000.0 ; // The integer part is line number and the decimal part is timestamp
      pt.curvature = s*0.1;
      pcl_in.push_back(pt);
    }
  }

  unsigned long timebase_ns = livox_data[0]->timebase;
  ros::Time timestamp;
  timestamp.fromNSec(timebase_ns);

  sensor_msgs::PointCloud2 pcl_ros_msg;
  pcl::toROSMsg(pcl_in, pcl_ros_msg);
  pcl_ros_msg.header.stamp.fromNSec(timebase_ns);
  pcl_ros_msg.header.frame_id = "/livox";
  pub_pcl_out1.publish(pcl_ros_msg);
  livox_data.clear();
}

int main(int argc, char** argv) {
  ros::init(argc, argv, "livox_repub");
  ros::NodeHandle nh;

  ROS_INFO("start livox_repub");

  ros::Subscriber sub_livox_msg1 = nh.subscribe<livox_ros_driver::CustomMsg>(
      "/livox/lidar", 100, LivoxMsgCbk1);
  pub_pcl_out1 = nh.advertise<sensor_msgs::PointCloud2>("/livox_pcl0", 100);

  ros::spin();
}

vi livox_repub.launch

<launch>

  <node pkg="livox_repub" type="livox_repub" name="livox_repub" output="screen" >
  <remap from="/livox/lidar" to="/livox/lidar" />
  </node>

</launch>
  1. Compile and run
cd ../../
catkin_make
source devel/setup.bash 
roslaunch livox_repub livox_repub.launch
  1. Play bag file
    Note: After the third step, open a new shell and cd to the bag file path.
    rosbag play xxxx.bag

  2. Convert to pcd
    Open a new shell
    In bag path: rosrun pcl_ros pointcloud_to_pcd input:=/livox_pcl0

    pcd will be output in the root directory

    Parsing pictures

Method 1: (This method can parse out jpg files with timestamps)

Create the following bag_to_jpg.py file under the bag folder:

#Bag file parsing jpg script
#coding:utf-8
import roslib;
import rosbag
import rospy
import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
from cv_bridge import CvBridgeError

path='/tmp/root/model_saas_data/zhangsihao/image/' #The path to store images on the server
class ImageCreator():
    def __init__(self):
        self.bridge = CvBridge()
        with rosbag.Bag('/tmp/root/model_saas_data/zhangsihao/rosbag_20220414_e01_2022-04-14-19-43-26.bag', 'r') as bag:   #The bag file to read (absolute path on the server);
            for topic,msg,t in bag.read_messages():
                if topic == "/cam_front_center_0/csi_cam/image_raw_resize":  #image's topic;
                        try:
                            # sensor_msgs/CompressedImage image type,Use the following method
                            # cv_image = self.bridge.compressed_imgmsg_to_cv2(msg,"bgr8")
                            cv_image = self.bridge.imgmsg_to_cv2(msg,"bgr8")
                        except CvBridgeError as e:
                            print(e)
                        timestr = "%.6f" %  msg.header.stamp.to_sec() #%.6f means there are 6 digits after the decimal point, which can be modified according to the accuracy;
                        image_name = timestr+ ".jpg"#Image naming: timestamp.jpg
                        cv2.imwrite(path+image_name, cv_image)  #Save


if __name__ == '__main__':
    try:
        image_creator = ImageCreator()
    except rospy.ROSInterruptException:
        pass

After running successfully, you can view the parsed .jpg file with time stamp in the image folder

Method 2: (This method uses the ros tool, and the jpg file name is parsed in order)

Create a configuration file for export.launch, the file content is as follows:

<launch> <node pkg="rosbag" type="play" name="rosbag" args="
/tmp/root/model_saas_data/zhangsihao/rosbag_20220414_e01_2022-04-14-19-43-26.bag"/> <node name="extract" pkg="image_view"
type="extract_images" respawn="false" output="screen" cwd="ROS_HOME"> <remap
from="image" to="/cam_front_center_0/csi_cam/image_raw_resize"/> </node> </launch>

/tmp/root/model_saas_data/zhangsihao/rosbag_20220414_e01_2022-04-14-19-43-26.bag

The path of the .bag file that needs to be parsed.

/cam_front_center_0/csi_cam/image_raw_resize

The name of the topic you want to parse

Create a new terminal, cd to the export.launch folder, and run the code as follows

$ roslaunch export.launch

The parsed image is in the .ros directory under /tmp

Upload to the Platform

When you have the converted .pcd and image files, you can upload to the platform.
See more details at upload dataset page.