ros2_interfaces_rolling/mavros_msgs/msg/
camera_image_captured.rs1use serde::{Deserialize, Serialize};
2
3#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
4pub struct CameraImageCaptured {
5 pub header: crate::std_msgs::msg::Header,
6 pub orientation: crate::geometry_msgs::msg::Quaternion,
7 pub geo: crate::geographic_msgs::msg::GeoPoint,
8 pub relative_alt: f32,
9 pub image_index: i32,
10 pub capture_result: i8,
11 pub file_url: ::std::string::String,
12}
13
14impl Default for CameraImageCaptured {
15 fn default() -> Self {
16 CameraImageCaptured {
17 header: crate::std_msgs::msg::Header::default(),
18 orientation: crate::geometry_msgs::msg::Quaternion::default(),
19 geo: crate::geographic_msgs::msg::GeoPoint::default(),
20 relative_alt: 0.0,
21 image_index: 0,
22 capture_result: 0,
23 file_url: ::std::string::String::new(),
24 }
25 }
26}
27
28impl ros2_client::Message for CameraImageCaptured {}