Extraction Tool¶
The Extraction Tool is the core of ROSData. It truly was the main reason why we developed the ROSData tools. To make the extraction of data from ROSBags as easy as possible and not require the creation of a script for every different dataset collected.
The extraction tool requires you to write simple extraction config file. This config file is a YAML file defining the data you want extracted and to which folder you wanted it extracted. This means once you have created an extraction config file for a specific robot, platform, or ROS system, you can easily reuse that one config file and share it with your colleagues. We find this works really well with students and researchers who aren’t familiar with ROS and need to get a project moving quickly. We can quickly teach them how to turn on the machine and how to record a ROSBag, and then simply provide them with the YAML file for extraction.
The tool can currently extract the following types of messages:
ROS Message Type |
Ouput Format |
---|---|
tf2_msgs/TFMessage |
CSV File |
sensor_msgs/CompressedImage |
Folder of Images, and if requested, a CSV with transforms |
sensor_msgs/Image |
Folder of Images, and if requested, a CSV with transforms |
sensor_msgs/PointCloud2 |
Folder of Point Clouds, and if requested, a CSV with transforms |
sensor_msgs/CameraInfo |
YAML File |
sensor_msgs/NavSatFix |
CSV File |
Important Note: if your sensor_msgs/PointCloud2
topic is from a stereo camera you will need to apply a filter. More information can be found here. If you are using Python Open3D, this Link Open3D Utils Package (link to come) has some great tools to help make filtering really easy.
Extraction Config File¶
The extraction config file is a YAML file. This file is used to specify what data should be extracted from a ROSBag and where it should be extracted. Currently only three types of high level keys are supported by the tool. These keys are: transorm_<id>
; camera_info_<id>
; and topic_<id>
. The <id>
is simply a unique number defined by you. Each key is used to extract data in a specific format for a specific set of ROS message types. The message types associated with each key are:
Extraction Config Key |
Associated ROS Message Types |
---|---|
|
tf2_msgs/TFMessage |
|
sensor_msgs/CameraInfo |
|
|
You can extract as many of each message type from your ROSBag by simply utilising unique IDs. For example, if you wish to extract a CSV file for the transform map
to odom
, as well as map
to base_link
you could simply have two transform keys (e.g., transform_0
and transform_1
), one for each. If your ROS system has a disconnected transform tree resulting in multiple tree roots, can specify the tree root in the config file using the key tree_root
.
Arguments¶
Transforms¶
transform_<id>:
parent_frame: <parent_frame> # required - used to specify the parent/origin frame
child_frame: <child_frame> # required - used to specify a child/destination frame
filename: <filename> # optional - used to specify a filename, the file extension .csv will be appended. Defaults to transform_<id>.csv
output_destination: <relative_destination> # optional - used to specify a directory relative to the root output directory to save the CSV file. Defaults to the root output directory.
Camera Info¶
camera_info_<id>:
topic_name: <camera_info_topic> # required - used to specify the name ofthe camera info topic
filename: <filename> # optional - used to specify a filename, the file extension .yaml will be appended. Defaults to camera_info_<id>.yaml
output_destination: <relative_destination> # optional - used to specify a directory relative to the root output directory to save the YAML file. Defaults to the root output directory.
Topics¶
The configuration for most topics includes the following options.
topic_<id>:
topic_name: <ros_topic_name> # required - used to specify the name of the topic
message_type: <ros_message_type> # required - determines the data extraction method
output_destination: <relative_destination> # optional - used to specify a directory relative to the root output directory to save the topic data. Defaults to the root_output_directory/topic_<id>.
filename_template: <filename_template> # optional - used as a filename template string (e.g. `image_%06d-<ros_timestamp>`), the appropriate file_extenstion will be automatically appended. Only a single topic index and ROS timestamp can be included in the template. Use the Python `%d` string formatter, or derivate of, to specify the topic index and use `<ros_timestamp>` to include the ROS topic timestamp as a string which will be in the format `<seconds>_<nanaseconds>`. Defaults to `frame_%06d`
transforms: # optional - only required if wish to output a CSV(s) containing transform data associated with the topic. Can specify multiple transforms to generate multiple CSV files all with different parameters
- parent_frame: <parent_frame_1> # required - used to specify the parent/origin frame
child_frame: <child_frame> # optional - used to specify the child/destination frame. Defaults to the frame ID stored in the topic
selection_method: <method_1> # optional - used to specify the method to determine the transform associated with each message within the topic. Options are exact, recent, nearest, and interpolate. See lookup_transform in rosdata/rosbag_transforms.py for more details on methods.
lookup_limit: <seconds_1> # optional - used to specify a lookup limit when determining the transform. See lookup_transform in rosdata/rosbag_transforms.py for more details on methods.
chain_limit: <seconds_1> # optional - used to specify a transform chain differential limit when determining the transform. See lookup_transform in rosdata/rosbag_transforms.py for more details on methods.
filename: <filename_1> # optional - used to specify a filename, the file extension .csv will be appended. Defaults to topic_<id>.csv
output_destination: <relative_destination_1> # optional - used to specify a directory relative to the root output directory to save the CSV file. Defaults to the root output directory.
- parent_frame: <parent_frame_2> # required - used to specify the parent/origin frame
child_frame: <child_frame> # optional - used to specify the child/destination frame. Defaults to the frame ID stored in the topic
selection_method: <method_2> # optional - used to specify the method to determine the transform associated with each message within the topic. Options are exact, recent, nearest, and interpolate. See lookup_transform in rosdata/rosbag_transforms.py for more details on methods.
lookup_limit: <seconds_2> # optional - used to specify a lookup limit when determining the transform. See lookup_transform in rosdata/rosbag_transforms.py for more details on methods.
chain_limit: <seconds_2> # optional - used to specify a transform chain differential limit when determining the transform. See lookup_transform in rosdata/rosbag_transforms.py for more details on methods.
filename: <filename_2> # optional - used to specify a filename, the file extension .csv will be appended. Defaults to topic_<id>.csv
output_destination: <relative_destination_2> # optional - used to specify a directory relative to the root output directory to save the CSV file. Defaults to the root output directory.
The configuration for the sensor_msgs/NavSatFix
has a reduced set of options.
topic_<id>:
topic_name: <ros_topic_name> # required - used to specify the name of the topic
message_type: <ros_message_type> # required - determines the data extraction method
output_destination: <relative_destination> # optional - used to specify a directory relative to the root output directory to save the topic data. Defaults to the root_output_directory/topic_<id>.
filename: <filename_template> # optional - used to specify a filename, the file extension .yaml will be appended. Defaults to topic_<id>.csv
A Complete Example¶
tree_root: map
transform_0:
parent_frame: map
child_frame: base_link
output_destination: data_files
filename: poses
camera_info_0:
topic_name: /pylon_camera_node/camera_info
filename: camera_info
output_destination: data_files
topic_0:
topic_name: /os1_cloud_node/points
message_type: sensor_msgs/PointCloud2
filename_template: pcd_%06d-<ros_timestamp>
output_destination: pointclouds
transforms:
- parent_frame: map
child_frame: ouster1/os1_lidar
selection_method: interpolate
lookup_limit: 0.5
chain_limit: 1.0
filename: pointclouds_map_poses
output_destination: data_files
- parent_frame: base_link
child_frame: ouster1/os1_lidar
selection_method: interpolate
lookup_limit: None
chain_limit: None
filename: pointclouds_baselink_poses
output_destination: data_files
topic_1:
topic_name: /pylon_camera_node/image_raw
message_type: sensor_msgs/Image
filename_template: image_%06d-<ros_timestamp>
output_destination: images
topic_2:
topic_name: /vectornav/GPS
message_type: sensor_msgs/NavSatFix
output_destination: data_files
filename: gps_data