This package provides a relatively flexible way of handling topic conversion/subscription for ROS nodes that need a large amount of data converted to torch.
NOTE: The datatypes for this package are currently defined in torch_coordinator.
New to ROS2, classes need to be a Node in order to instantiate subscribers, etc. Thus, the current way to use this converter is something like the following:
import rclpy
from rclpy.node import Node
from rclpy.executors import MultiThreadedExecutor
from ros_torch_converter.converter import ROSTorchConverter
class ExampleNode(Node):
def __init__(self, converter):
self.converter = converter
self.timer = self.get_timer(1.0, self.callback)
def callback(self):
if self.converter.can_get_data():
#dict of torch data
data = self.converter.get_data()
if __name__ == '__main__':
converter_node = ROSTorchConverter(config)
plt_node = MPLPlotter(converter_node)
executor = MultiThreadedExecutor()
executor.add_node(converter_node)
executor.add_node(plt_node)
try:
executor.spin()
finally:
converter_node.destroy_node()
plt_node.destroy_node()
rclpy.shutdown()The ROS-Torch converter requires a config yaml (example in configs/costmap_speedmap.yaml) that specifies the topics to listen to and how to convert.
Extract kitti format data from rosbag:
python3 scripts/ros2bag_2_kitti.py --config config/kitti_config/super_odometry_sensors.yaml --src_dir [mcap_dir] --dst_dir [output_dir]
Export full scene reconstruction from SLAM to PCD:
python3 scripts/slam_2_pcd.py --config config/kitti_config/slam_2_pcd.yaml
Post-process SLAM dataset (depth, camera poses):
python3 scripts/get_slam_data.py --dataset [dataset_dir] --config config/kitti_config/get_slam_data_rgb.yaml #_thermal
- run with
--idx [idx] --debugfor single frame debug and viz --resumeto resume from last processed frame--seq_to [idx]to process a specific sequence
Post-process thermal data (rectify, process):
python3 scripts/get_thermal_data.py --dataset [dataset_dir] --config config/kitti_config/get_thermal_data.yaml
- run this if your bag doesn't already have _rect or _processed thermal topics
More details on Slite.
When you make changes to the datatypes, make sure this test passes:
python3 -m pytest tests/test.py