diff --git a/a2d2_ros_preparer/src/converter.cpp b/a2d2_ros_preparer/src/converter.cpp index ff85337..f5ca6b3 100644 --- a/a2d2_ros_preparer/src/converter.cpp +++ b/a2d2_ros_preparer/src/converter.cpp @@ -45,6 +45,7 @@ namespace a2d2_ros_preparer { auto lidar_scan_stream = LidarScanStream(vehicle_configuration.GetLidarDataDirectoryPath(), vehicle_configuration.GetCameraIdentifiers(), vehicle_configuration.GetLidarIdentifiers(), + options.lidar_sensor_id_remappings(), vehicle_configuration.GetCameraToBaseAffineTransforms(), vehicle_configuration.GetLidarToBaseAffineTransforms(), options.filter_start_timestamp(), diff --git a/a2d2_ros_preparer/src/lidar/lidar_scan_stream.cpp b/a2d2_ros_preparer/src/lidar/lidar_scan_stream.cpp index a92f0d9..4349852 100644 --- a/a2d2_ros_preparer/src/lidar/lidar_scan_stream.cpp +++ b/a2d2_ros_preparer/src/lidar/lidar_scan_stream.cpp @@ -28,6 +28,7 @@ namespace a2d2_ros_preparer { LidarScanStream::LidarScanStream(const std::filesystem::path& lidar_data_directory, const std::vector& camera_identifiers, std::vector lidar_identifiers, + const std::map> sensor_id_remappings, std::map camera_to_base_affine_transformation, std::map lidar_to_base_affine_transformation, std::optional