mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
Copter: move update_sensor_flags to GCS_Copter.cpp
This commit is contained in:
parent
cb95bf7814
commit
c622645ff1
228
ArduCopter/GCS_Copter.cpp
Normal file
228
ArduCopter/GCS_Copter.cpp
Normal file
@ -0,0 +1,228 @@
|
||||
#include "GCS_Copter.h"
|
||||
|
||||
#include "Copter.h"
|
||||
|
||||
// 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_Copter::update_sensor_status_flags(void)
|
||||
{
|
||||
// default sensors present
|
||||
control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT;
|
||||
|
||||
// first what sensors/controllers we have
|
||||
if (copter.g.compass_enabled) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present
|
||||
}
|
||||
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 PRECISION_LANDING == ENABLED
|
||||
if (copter.precland.enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
const AP_VisualOdom *visual_odom = AP::visualodom();
|
||||
if (visual_odom && visual_odom->enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
const Copter::ap_t &ap = copter.ap;
|
||||
|
||||
if (ap.rc_receiver_present) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
}
|
||||
const AP_Logger &logger = AP::logger();
|
||||
if (logger.logging_present()) { // primary logging only (usually File)
|
||||
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
|
||||
}
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (copter.g2.proximity.sensor_present()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||
}
|
||||
#endif
|
||||
#if AC_FENCE == ENABLED
|
||||
if (copter.fence.sys_status_present()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_GEOFENCE;
|
||||
}
|
||||
#endif
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
const RangeFinder *rangefinder = RangeFinder::get_singleton();
|
||||
if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
#endif
|
||||
|
||||
// all sensors are present except these, which may be set as enabled below:
|
||||
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL &
|
||||
~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL &
|
||||
~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS &
|
||||
~MAV_SYS_STATUS_LOGGING &
|
||||
~MAV_SYS_STATUS_SENSOR_BATTERY &
|
||||
~MAV_SYS_STATUS_GEOFENCE &
|
||||
~MAV_SYS_STATUS_SENSOR_LASER_POSITION &
|
||||
~MAV_SYS_STATUS_SENSOR_PROXIMITY);
|
||||
|
||||
switch (copter.control_mode) {
|
||||
case AUTO:
|
||||
case AVOID_ADSB:
|
||||
case GUIDED:
|
||||
case LOITER:
|
||||
case RTL:
|
||||
case CIRCLE:
|
||||
case LAND:
|
||||
case POSHOLD:
|
||||
case BRAKE:
|
||||
case THROW:
|
||||
case SMART_RTL:
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
||||
break;
|
||||
case ALT_HOLD:
|
||||
case GUIDED_NOGPS:
|
||||
case SPORT:
|
||||
case AUTOTUNE:
|
||||
case FLOWHOLD:
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||
break;
|
||||
default:
|
||||
// stabilize, acro, drift, and flip have no automatic x,y or z control (i.e. all manual)
|
||||
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;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
#if AC_FENCE == ENABLED
|
||||
if (copter.fence.sys_status_enabled()) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE;
|
||||
}
|
||||
#endif
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (copter.g2.proximity.sensor_enabled()) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// default to all healthy
|
||||
control_sensors_health = control_sensors_present;
|
||||
|
||||
const AP_Baro &barometer = AP::baro();
|
||||
if (!barometer.all_healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||
}
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
const Compass &compass = AP::compass();
|
||||
if (!copter.g.compass_enabled || !compass.healthy() || !ahrs.use_compass()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
}
|
||||
if (!gps.is_healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_GPS;
|
||||
}
|
||||
if (!ap.rc_receiver_present || copter.failsafe.radio) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
}
|
||||
#if OPTFLOW == ENABLED
|
||||
if (!optflow || !optflow->healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
}
|
||||
#endif
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
if (copter.precland.enabled() && !copter.precland.healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
if (visual_odom && visual_odom->enabled() && visual_odom->healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
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 (ahrs.initialised() && !ahrs.healthy()) {
|
||||
// AHRS subsystem is unhealthy
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
|
||||
}
|
||||
|
||||
if (logger.logging_failed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_LOGGING;
|
||||
}
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (copter.g2.proximity.sensor_failed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
switch (copter.terrain.status()) {
|
||||
case AP_Terrain::TerrainStatusDisabled:
|
||||
break;
|
||||
case AP_Terrain::TerrainStatusUnhealthy:
|
||||
// To-Do: restore unhealthy terrain status reporting once terrain is used in copter
|
||||
//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
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
if (copter.rangefinder_state.enabled) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
if (!rangefinder || !rangefinder->has_data_orient(ROTATION_PITCH_270)) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!ap.initialised || ins.calibrating()) {
|
||||
// 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 (!copter.battery.healthy() || copter.battery.has_failsafed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_BATTERY;
|
||||
}
|
||||
#if AC_FENCE == ENABLED
|
||||
if (copter.fence.sys_status_failed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_GEOFENCE;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// give mask of error flags to Frsky_Telemetry
|
||||
copter.frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present);
|
||||
#endif
|
||||
}
|
@ -182,231 +182,6 @@ void Copter::init_proximity(void)
|
||||
#endif
|
||||
}
|
||||
|
||||
// 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_Copter::update_sensor_status_flags(void)
|
||||
{
|
||||
// default sensors present
|
||||
control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT;
|
||||
|
||||
// first what sensors/controllers we have
|
||||
if (copter.g.compass_enabled) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present
|
||||
}
|
||||
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 PRECISION_LANDING == ENABLED
|
||||
if (copter.precland.enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
const AP_VisualOdom *visual_odom = AP::visualodom();
|
||||
if (visual_odom && visual_odom->enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
const Copter::ap_t &ap = copter.ap;
|
||||
|
||||
if (ap.rc_receiver_present) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
}
|
||||
const AP_Logger &logger = AP::logger();
|
||||
if (logger.logging_present()) { // primary logging only (usually File)
|
||||
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
|
||||
}
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (copter.g2.proximity.sensor_present()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||
}
|
||||
#endif
|
||||
#if AC_FENCE == ENABLED
|
||||
if (copter.fence.sys_status_present()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_GEOFENCE;
|
||||
}
|
||||
#endif
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
const RangeFinder *rangefinder = RangeFinder::get_singleton();
|
||||
if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
#endif
|
||||
|
||||
// all sensors are present except these, which may be set as enabled below:
|
||||
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL &
|
||||
~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL &
|
||||
~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS &
|
||||
~MAV_SYS_STATUS_LOGGING &
|
||||
~MAV_SYS_STATUS_SENSOR_BATTERY &
|
||||
~MAV_SYS_STATUS_GEOFENCE &
|
||||
~MAV_SYS_STATUS_SENSOR_LASER_POSITION &
|
||||
~MAV_SYS_STATUS_SENSOR_PROXIMITY);
|
||||
|
||||
switch (copter.control_mode) {
|
||||
case AUTO:
|
||||
case AVOID_ADSB:
|
||||
case GUIDED:
|
||||
case LOITER:
|
||||
case RTL:
|
||||
case CIRCLE:
|
||||
case LAND:
|
||||
case POSHOLD:
|
||||
case BRAKE:
|
||||
case THROW:
|
||||
case SMART_RTL:
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
||||
break;
|
||||
case ALT_HOLD:
|
||||
case GUIDED_NOGPS:
|
||||
case SPORT:
|
||||
case AUTOTUNE:
|
||||
case FLOWHOLD:
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||
break;
|
||||
default:
|
||||
// stabilize, acro, drift, and flip have no automatic x,y or z control (i.e. all manual)
|
||||
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;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
#if AC_FENCE == ENABLED
|
||||
if (copter.fence.sys_status_enabled()) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE;
|
||||
}
|
||||
#endif
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (copter.g2.proximity.sensor_enabled()) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// default to all healthy
|
||||
control_sensors_health = control_sensors_present;
|
||||
|
||||
const AP_Baro &barometer = AP::baro();
|
||||
if (!barometer.all_healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||
}
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
const Compass &compass = AP::compass();
|
||||
if (!copter.g.compass_enabled || !compass.healthy() || !ahrs.use_compass()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
}
|
||||
if (!gps.is_healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_GPS;
|
||||
}
|
||||
if (!ap.rc_receiver_present || copter.failsafe.radio) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
}
|
||||
#if OPTFLOW == ENABLED
|
||||
if (!optflow || !optflow->healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
}
|
||||
#endif
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
if (copter.precland.enabled() && !copter.precland.healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
if (visual_odom && visual_odom->enabled() && visual_odom->healthy()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
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 (ahrs.initialised() && !ahrs.healthy()) {
|
||||
// AHRS subsystem is unhealthy
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
|
||||
}
|
||||
|
||||
if (logger.logging_failed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_LOGGING;
|
||||
}
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (copter.g2.proximity.sensor_failed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
switch (copter.terrain.status()) {
|
||||
case AP_Terrain::TerrainStatusDisabled:
|
||||
break;
|
||||
case AP_Terrain::TerrainStatusUnhealthy:
|
||||
// To-Do: restore unhealthy terrain status reporting once terrain is used in copter
|
||||
//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
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
if (copter.rangefinder_state.enabled) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
if (!rangefinder || !rangefinder->has_data_orient(ROTATION_PITCH_270)) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!ap.initialised || ins.calibrating()) {
|
||||
// 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 (!copter.battery.healthy() || copter.battery.has_failsafed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_BATTERY;
|
||||
}
|
||||
#if AC_FENCE == ENABLED
|
||||
if (copter.fence.sys_status_failed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_GEOFENCE;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// give mask of error flags to Frsky_Telemetry
|
||||
copter.frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present);
|
||||
#endif
|
||||
}
|
||||
|
||||
// init visual odometry sensor
|
||||
void Copter::init_visual_odom()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user