mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: Report battery failsafes via sys_status
This commit is contained in:
parent
e12b932432
commit
f017073077
@ -203,8 +203,12 @@ void Plane::update_sensor_status_flags(void)
|
|||||||
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
|
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
|
||||||
}
|
}
|
||||||
|
|
||||||
// all present sensors enabled by default except rate control, attitude stabilization, yaw, altitude, position control, geofence and motor output which we will set individually
|
if (plane.battery.healthy()) {
|
||||||
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL & ~MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION & ~MAV_SYS_STATUS_SENSOR_YAW_POSITION & ~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL & ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL & ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & ~MAV_SYS_STATUS_GEOFENCE & ~MAV_SYS_STATUS_LOGGING);
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_BATTERY;
|
||||||
|
}
|
||||||
|
|
||||||
|
// all present sensors enabled by default except rate control, attitude stabilization, yaw, altitude, position control, geofence, motor, and battery output which we will set individually
|
||||||
|
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL & ~MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION & ~MAV_SYS_STATUS_SENSOR_YAW_POSITION & ~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL & ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL & ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & ~MAV_SYS_STATUS_GEOFENCE & ~MAV_SYS_STATUS_LOGGING & ~MAV_SYS_STATUS_SENSOR_BATTERY);
|
||||||
|
|
||||||
if (airspeed.enabled() && airspeed.use()) {
|
if (airspeed.enabled() && airspeed.use()) {
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
||||||
@ -218,6 +222,10 @@ void Plane::update_sensor_status_flags(void)
|
|||||||
control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
|
control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (g.fs_batt_voltage > 0 || g.fs_batt_mah > 0) {
|
||||||
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY;
|
||||||
|
}
|
||||||
|
|
||||||
switch (control_mode) {
|
switch (control_mode) {
|
||||||
case MANUAL:
|
case MANUAL:
|
||||||
break;
|
break;
|
||||||
@ -364,6 +372,11 @@ void Plane::update_sensor_status_flags(void)
|
|||||||
control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
||||||
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (plane.failsafe.low_battery) {
|
||||||
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_BATTERY;
|
||||||
|
}
|
||||||
|
|
||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
// give mask of error flags to Frsky_Telemetry
|
// give mask of error flags to Frsky_Telemetry
|
||||||
frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present);
|
frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present);
|
||||||
|
Loading…
Reference in New Issue
Block a user