mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
MAVLink: update compass health in SYS_STATUS
this will make it easier to tell if a I2C error occurred in flight
This commit is contained in:
parent
daa4712078
commit
fddfb0b1a3
@ -153,6 +153,13 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
||||
// at the moment all sensors/controllers are assumed healthy
|
||||
control_sensors_health = control_sensors_present;
|
||||
|
||||
if (!compass.healthy) {
|
||||
control_sensors_health &= ~(1<<2); // compass
|
||||
}
|
||||
if (!compass.use_for_yaw()) {
|
||||
control_sensors_enabled &= ~(1<<2); // compass
|
||||
}
|
||||
|
||||
uint16_t battery_current = -1;
|
||||
uint8_t battery_remaining = -1;
|
||||
|
||||
|
@ -190,6 +190,13 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
||||
// at the moment all sensors/controllers are assumed healthy
|
||||
control_sensors_health = control_sensors_present;
|
||||
|
||||
if (!compass.healthy) {
|
||||
control_sensors_health &= ~(1<<2); // compass
|
||||
}
|
||||
if (!compass.use_for_yaw()) {
|
||||
control_sensors_enabled &= ~(1<<2); // compass
|
||||
}
|
||||
|
||||
uint16_t battery_current = -1;
|
||||
uint8_t battery_remaining = -1;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user