pub struct SYS_STATUS_DATA {Show 16 fields
pub onboard_control_sensors_present: MavSysStatusSensor,
pub onboard_control_sensors_enabled: MavSysStatusSensor,
pub onboard_control_sensors_health: MavSysStatusSensor,
pub load: u16,
pub voltage_battery: u16,
pub current_battery: i16,
pub drop_rate_comm: u16,
pub errors_comm: u16,
pub errors_count1: u16,
pub errors_count2: u16,
pub errors_count3: u16,
pub errors_count4: u16,
pub battery_remaining: i8,
pub onboard_control_sensors_present_extended: MavSysStatusSensorExtended,
pub onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended,
pub onboard_control_sensors_health_extended: MavSysStatusSensorExtended,
}
common
only.Expand description
id: 1 The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout..
Fields§
§onboard_control_sensors_present: MavSysStatusSensor
Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present..
onboard_control_sensors_enabled: MavSysStatusSensor
Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled..
onboard_control_sensors_health: MavSysStatusSensor
Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy..
load: u16
Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000.
voltage_battery: u16
Battery voltage, UINT16_MAX: Voltage not sent by autopilot.
current_battery: i16
Battery current, -1: Current not sent by autopilot.
drop_rate_comm: u16
Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV).
errors_comm: u16
Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV).
errors_count1: u16
Autopilot-specific errors.
errors_count2: u16
Autopilot-specific errors.
errors_count3: u16
Autopilot-specific errors.
errors_count4: u16
Autopilot-specific errors.
battery_remaining: i8
Battery energy remaining, -1: Battery remaining energy not sent by autopilot.
onboard_control_sensors_present_extended: MavSysStatusSensorExtended
Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present..
onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended
Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled..
onboard_control_sensors_health_extended: MavSysStatusSensorExtended
Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy..
Implementations§
Source§impl SYS_STATUS_DATA
impl SYS_STATUS_DATA
pub const ENCODED_LEN: usize = 43usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for SYS_STATUS_DATA
impl Clone for SYS_STATUS_DATA
Source§fn clone(&self) -> SYS_STATUS_DATA
fn clone(&self) -> SYS_STATUS_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more