Deserializing multiple topics from a ROS2 Bag (SQLite3)
I'm using ROS 2 Dashing, Ubuntu 18.04.
I've recorded data with ros2 bag
as explained in the ROS2 tutorial from the turtlesim
package.
First, I started the node:
ros2 run turtlesim turtlesim_node
ros2 run turtlesim turtle_teleop_key
then I recorded all three topics with
ros2 bag record -a
namely, the topics are:
/turtle1/cmd_vel
of typegeometry_msgs/msg/Twist
/turtle1/color_sensor
of typeturtlesim/msg/Color
/turtle1/pose
of typeturtlesim/msg/Pose
I am interested in viewing the data recorded as text files, but the .db3 SQLite3 file inside the bag shows the data as BLOB (binary large object), stating: Binary data cannot be viewed with the text editor
.
I am able to deserialize data from the bag if there is one topic only, but I'm not sure how to deserialize multiple topics.
The approach I'm trying (found here) is to use rosbag2::converter_interfaces::SerializationFormatConverter
:
void deserialize(const std::string datatype_name){
//Opening part:
rosbag2::SequentialReader reader;
rosbag2::ConverterOptions converter_options{};
converter_options.input_serialization_format = "cdr";
converter_options.output_serialization_format = "cdr";
reader.open(storage_options, converter_options);
// Load the topics
auto topics = reader.get_all_topics_and_types();
rosbag2::SerializationFormatConverterFactory factory;
std::unique_ptr<rosbag2::converter_interfaces::SerializationFormatDeserializer> cdr_deserializer_;
cdr_deserializer_ = factory.load_deserializer("cdr");
// Iterate through the file
while(reader.has_next()){
auto serialized_message = reader.read_next();
auto ros_message = std::make_shared<rosbag2_introspection_message_t>();
ros_message->time_stamp = 0;
ros_message->message = nullptr;
ros_message->allocator = rcutils_get_default_allocator();
auto type_support = rosbag2::get_typesupport(datatype_name, "rosidl_typesupport_cpp");
if(datatype_name == "geometry_msgs/msg/Twist"){
ros_message->message = new geometry_msgs::msg::Twist();
}
else if(datatype_name == "turtlesim/msg/Pose"){
ros_message->message = new turtlesim::msg::Pose();
}
else if(datatype_name == "turtlesim/msg/Color"){
ros_message->message = new turtlesim::msg::Color();
}
else{
std::cout << "not supported" << std::endl;
}
if(ros_message->message){
cdr_deserializer_->deserialize(serialized_message, type_support, ros_message);
// optionally, print:
// std::cout << (int)msgColor.r << " " << (int)msgColor.g << " " << (int)msgColor.b << std::endl;
}
}
}
But the data does not deserialize correctly except for the first type, I assume it is because it should receive an offset of some sort before deserialitazion starts.
[INFO] [rosbag2_storage]: Opened database '../rosbag2_test_data_multi'.
0x96d480 turtlesim/msg/Pose Pose
0x96d480 turtlesim/msg/Pose Pose
terminate called after throwing an instance of 'eprosima::fastcdr::exception::NotEnoughMemoryException'
what(): Not enough memory in the buffer stream
Is there a way to set a combination of datatype_name
in the type_support?
auto type_support = rosbag2::get_typesupport(datatype_name, "rosidl_typesupport_cpp");
Is there a simpler way to convert ROS2 Bag files into csv/text without changing the current version of Dashing?
I'm not limited to C++, I found some cool python libraries that could help but they do not support Dashing unfortunately.
Thank you for your help.