use std::collections::BTreeMap;
use super::MessageDecoder;
use crate::parsers::MessageParser;
use crate::parsers::ros2msg::Ros2MessageParser;
use crate::parsers::ros2msg::geometry_msgs::PoseStampedMessageParser;
use crate::parsers::ros2msg::rcl_interfaces::LogMessageParser;
use crate::parsers::ros2msg::sensor_msgs::{
BatteryStateMessageParser, CameraInfoMessageParser, CompressedImageMessageParser,
FluidPressureMessageParser, IlluminanceMessageParser, ImageMessageParser, ImuMessageParser,
JointStateMessageParser, JoyMessageParser, MagneticFieldMessageParser, NavSatFixMessageParser,
PointCloud2MessageParser, RangeMessageParser, RelativeHumidityMessageParser,
TemperatureMessageParser,
};
use crate::parsers::ros2msg::std_msgs::{
Float64ArrayMessageParser, Float64MultiArrayMessageParser, StringMessageParser,
};
use crate::parsers::ros2msg::tf2_msgs::tf_message::TfMessageParser;
type ParserFactory = fn(usize) -> Box<dyn MessageParser>;
#[derive(Debug)]
pub struct McapRos2Decoder {
registry: BTreeMap<String, ParserFactory>,
}
impl McapRos2Decoder {
const ENCODING: &str = "ros2msg";
fn empty() -> Self {
Self {
registry: BTreeMap::new(),
}
}
pub fn new() -> Self {
Self::empty()
.register_parser::<PoseStampedMessageParser>("geometry_msgs/msg/PoseStamped")
.register_parser::<LogMessageParser>("rcl_interfaces/msg/Log")
.register_parser::<BatteryStateMessageParser>("sensor_msgs/msg/BatteryState")
.register_parser::<CameraInfoMessageParser>("sensor_msgs/msg/CameraInfo")
.register_parser::<CompressedImageMessageParser>("sensor_msgs/msg/CompressedImage")
.register_parser::<FluidPressureMessageParser>("sensor_msgs/msg/FluidPressure")
.register_parser::<IlluminanceMessageParser>("sensor_msgs/msg/Illuminance")
.register_parser::<ImageMessageParser>("sensor_msgs/msg/Image")
.register_parser::<ImuMessageParser>("sensor_msgs/msg/Imu")
.register_parser::<JoyMessageParser>("sensor_msgs/msg/Joy")
.register_parser::<JointStateMessageParser>("sensor_msgs/msg/JointState")
.register_parser::<MagneticFieldMessageParser>("sensor_msgs/msg/MagneticField")
.register_parser::<NavSatFixMessageParser>("sensor_msgs/msg/NavSatFix")
.register_parser::<PointCloud2MessageParser>("sensor_msgs/msg/PointCloud2")
.register_parser::<RangeMessageParser>("sensor_msgs/msg/Range")
.register_parser::<RelativeHumidityMessageParser>("sensor_msgs/msg/RelativeHumidity")
.register_parser::<TemperatureMessageParser>("sensor_msgs/msg/Temperature")
.register_parser::<Float64ArrayMessageParser>("std_msgs/msg/Float64Array")
.register_parser::<Float64MultiArrayMessageParser>("std_msgs/msg/Float64MultiArray")
.register_parser::<StringMessageParser>("std_msgs/msg/String")
.register_parser::<TfMessageParser>("tf2_msgs/msg/TFMessage")
}
pub fn register_parser<T: Ros2MessageParser + 'static>(mut self, schema_name: &str) -> Self {
self.registry
.insert(schema_name.to_owned(), |n| Box::new(T::new(n)));
self
}
pub fn register_parser_with_factory(
mut self,
schema_name: &str,
factory: ParserFactory,
) -> Self {
self.registry.insert(schema_name.to_owned(), factory);
self
}
pub fn supports_schema(&self, schema_name: &str) -> bool {
self.registry.contains_key(schema_name)
}
}
impl Default for McapRos2Decoder {
fn default() -> Self {
Self::new()
}
}
impl MessageDecoder for McapRos2Decoder {
fn identifier() -> super::DecoderIdentifier {
"ros2msg".into()
}
fn supports_channel(&self, channel: &mcap::Channel<'_>) -> bool {
channel.schema.as_ref().is_some_and(|s| {
s.encoding.as_str() == Self::ENCODING && self.registry.contains_key(&s.name)
})
}
fn message_parser(
&self,
channel: &mcap::Channel<'_>,
num_rows: usize,
) -> Option<Box<dyn MessageParser>> {
let schema = channel.schema.as_ref()?;
if schema.encoding.as_str() != Self::ENCODING {
return None;
}
if let Some(make) = self.registry.get(&schema.name) {
Some(make(num_rows))
} else {
re_log::warn_once!(
"Message schema {:?} is currently not supported",
schema.name
);
None
}
}
}