2016-08-25 04:48:27 -03:00
# include "GCS_Plane.h"
# include "Plane.h"
2019-02-19 17:29:54 -04:00
// update error mask of sensors and subsystems. The mask
// uses the MAV_SYS_STATUS_* values from mavlink. If a bit is set
// then it indicates that the sensor or subsystem is present but
// not functioning correctly.
void GCS_Plane : : update_sensor_status_flags ( void )
{
// default sensors present
control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT ;
// first what sensors/controllers we have
if ( plane . g . compass_enabled ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_3D_MAG ; // compass present
}
const AP_Airspeed * airspeed = AP_Airspeed : : get_singleton ( ) ;
if ( airspeed & & airspeed - > enabled ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ;
}
const AP_GPS & gps = AP : : gps ( ) ;
if ( gps . status ( ) > AP_GPS : : NO_GPS ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_GPS ;
}
# if OPTFLOW == ENABLED
const OpticalFlow * optflow = AP : : opticalflow ( ) ;
if ( optflow & & optflow - > enabled ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW ;
}
# endif
if ( plane . geofence_present ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_GEOFENCE ;
}
if ( plane . have_reverse_thrust ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_REVERSE_MOTOR ;
}
const AP_Logger & logger = AP : : logger ( ) ;
if ( logger . logging_present ( ) ) { // primary logging only (usually File)
control_sensors_present | = MAV_SYS_STATUS_LOGGING ;
}
// 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 & & airspeed - > enabled ( ) & & airspeed - > use ( ) ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ;
}
if ( plane . geofence_enabled ( ) ) {
control_sensors_enabled | = MAV_SYS_STATUS_GEOFENCE ;
}
if ( logger . logging_enabled ( ) ) {
control_sensors_enabled | = MAV_SYS_STATUS_LOGGING ;
}
const AP_BattMonitor & battery = AP : : battery ( ) ;
if ( battery . num_instances ( ) > 0 ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_BATTERY ;
}
switch ( plane . control_mode ) {
case MANUAL :
break ;
case ACRO :
2019-02-17 14:42:05 -04:00
case QACRO :
2019-02-19 17:29:54 -04:00
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL ; // 3D angular rate control
break ;
case STABILIZE :
case FLY_BY_WIRE_A :
case AUTOTUNE :
case QSTABILIZE :
case QHOVER :
case QLAND :
case QLOITER :
case QAUTOTUNE :
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL ; // 3D angular rate control
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION ; // attitude stabilisation
break ;
case FLY_BY_WIRE_B :
case CRUISE :
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL ; // 3D angular rate control
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION ; // attitude stabilisation
break ;
case TRAINING :
if ( ! plane . training_manual_roll | | ! plane . training_manual_pitch ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL ; // 3D angular rate control
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION ; // attitude stabilisation
}
break ;
case AUTO :
case RTL :
case LOITER :
case AVOID_ADSB :
case GUIDED :
case CIRCLE :
case QRTL :
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL ; // 3D angular rate control
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION ; // attitude stabilisation
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_YAW_POSITION ; // yaw position
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL ; // altitude control
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL ; // X/Y position control
break ;
case INITIALISING :
break ;
}
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
if ( hal . util - > safety_switch_state ( ) ! = AP_HAL : : Util : : SAFETY_DISARMED ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS ;
}
// default: all present sensors healthy except baro, 3D_MAG, GPS, DIFFERNTIAL_PRESSURE. GEOFENCE always defaults to healthy.
control_sensors_health = control_sensors_present & ~ ( MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE |
MAV_SYS_STATUS_SENSOR_3D_MAG |
MAV_SYS_STATUS_SENSOR_GPS |
MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ) ;
control_sensors_health | = MAV_SYS_STATUS_GEOFENCE ;
AP_AHRS & ahrs = AP : : ahrs ( ) ;
if ( ahrs . initialised ( ) & & ! ahrs . healthy ( ) ) {
// AHRS subsystem is unhealthy
control_sensors_health & = ~ MAV_SYS_STATUS_AHRS ;
}
const AP_InertialSensor & ins = AP : : ins ( ) ;
if ( ahrs . have_inertial_nav ( ) & & ! ins . accel_calibrated_ok_all ( ) ) {
// trying to use EKF without properly calibrated accelerometers
control_sensors_health & = ~ MAV_SYS_STATUS_AHRS ;
}
const AP_Baro & barometer = AP : : baro ( ) ;
if ( barometer . all_healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE ;
}
const Compass & compass = AP : : compass ( ) ;
if ( plane . g . compass_enabled & & compass . healthy ( ) & & ahrs . use_compass ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_3D_MAG ;
}
if ( gps . status ( ) > = AP_GPS : : GPS_OK_FIX_3D & & gps . is_healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_GPS ;
}
# if OPTFLOW == ENABLED
if ( optflow & & optflow - > healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW ;
}
# endif
if ( ! ins . get_gyro_health_all ( ) | | ! ins . gyro_calibrated_ok_all ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_3D_GYRO ;
}
if ( ! ins . get_accel_health_all ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_3D_ACCEL ;
}
if ( airspeed & & airspeed - > all_healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ;
}
# if GEOFENCE_ENABLED
if ( plane . geofence_breached ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_GEOFENCE ;
}
# endif
if ( logger . logging_failed ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_LOGGING ;
}
if ( millis ( ) - plane . failsafe . last_valid_rc_ms < 200 ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_RC_RECEIVER ;
} else {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_RC_RECEIVER ;
}
# if AP_TERRAIN_AVAILABLE
switch ( plane . terrain . status ( ) ) {
case AP_Terrain : : TerrainStatusDisabled :
break ;
case AP_Terrain : : TerrainStatusUnhealthy :
control_sensors_present | = MAV_SYS_STATUS_TERRAIN ;
control_sensors_enabled | = MAV_SYS_STATUS_TERRAIN ;
break ;
case AP_Terrain : : TerrainStatusOK :
control_sensors_present | = MAV_SYS_STATUS_TERRAIN ;
control_sensors_enabled | = MAV_SYS_STATUS_TERRAIN ;
control_sensors_health | = MAV_SYS_STATUS_TERRAIN ;
break ;
}
# endif
const RangeFinder * rangefinder = RangeFinder : : get_singleton ( ) ;
if ( rangefinder & & rangefinder - > has_orientation ( ROTATION_PITCH_270 ) ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
if ( plane . g . rangefinder_landing ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
}
if ( rangefinder - > has_data_orient ( ROTATION_PITCH_270 ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
}
}
if ( plane . have_reverse_thrust ( ) & & SRV_Channels : : get_output_scaled ( SRV_Channel : : k_throttle ) < 0 ) {
control_sensors_enabled | = MAV_SYS_STATUS_REVERSE_MOTOR ;
control_sensors_health | = MAV_SYS_STATUS_REVERSE_MOTOR ;
}
if ( AP_Notify : : flags . initialising ) {
// while initialising the gyros and accels are not enabled
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 ) ;
}
if ( ! plane . battery . healthy ( ) | | plane . battery . has_failsafed ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_BATTERY ;
}
}