ros2_interfaces_rolling/mavros_msgs/msg/
sys_status.rs

1use serde::{Deserialize, Serialize};
2
3#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
4pub struct SysStatus {
5    pub header: crate::std_msgs::msg::Header,
6    pub sensors_present: u32,
7    pub sensors_enabled: u32,
8    pub sensors_health: u32,
9    pub load: u16,
10    pub voltage_battery: u16,
11    pub current_battery: i16,
12    pub battery_remaining: i8,
13    pub drop_rate_comm: u16,
14    pub errors_comm: u16,
15    pub errors_count1: u16,
16    pub errors_count2: u16,
17    pub errors_count3: u16,
18    pub errors_count4: u16,
19}
20
21impl Default for SysStatus {
22    fn default() -> Self {
23        SysStatus {
24            header: crate::std_msgs::msg::Header::default(),
25            sensors_present: 0,
26            sensors_enabled: 0,
27            sensors_health: 0,
28            load: 0,
29            voltage_battery: 0,
30            current_battery: 0,
31            battery_remaining: 0,
32            drop_rate_comm: 0,
33            errors_comm: 0,
34            errors_count1: 0,
35            errors_count2: 0,
36            errors_count3: 0,
37            errors_count4: 0,
38        }
39    }
40}
41
42impl ros2_client::Message for SysStatus {}