ros2_interfaces_rolling/stereo_msgs/msg/
disparity_image.rs

1use serde::{Deserialize, Serialize};
2
3#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
4pub struct DisparityImage {
5    pub header: crate::std_msgs::msg::Header,
6    pub image: crate::sensor_msgs::msg::Image,
7    pub f: f32,
8    pub t: f32,
9    pub valid_window: crate::sensor_msgs::msg::RegionOfInterest,
10    pub min_disparity: f32,
11    pub max_disparity: f32,
12    pub delta_d: f32,
13}
14
15impl Default for DisparityImage {
16    fn default() -> Self {
17        DisparityImage {
18            header: crate::std_msgs::msg::Header::default(),
19            image: crate::sensor_msgs::msg::Image::default(),
20            f: 0.0,
21            t: 0.0,
22            valid_window: crate::sensor_msgs::msg::RegionOfInterest::default(),
23            min_disparity: 0.0,
24            max_disparity: 0.0,
25            delta_d: 0.0,
26        }
27    }
28}
29
30impl ros2_client::Message for DisparityImage {}