mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Sub: move various sensor status flag updates up
This commit is contained in:
parent
b976442e64
commit
173611e819
@ -2,36 +2,48 @@
|
|||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// default sensors are present and healthy: gyro, accelerometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control
|
void GCS_Sub::update_vehicle_sensor_status_flags()
|
||||||
#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | 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_AHRS | MAV_SYS_STATUS_SENSOR_BATTERY)
|
|
||||||
|
|
||||||
void GCS_Sub::update_sensor_status_flags()
|
|
||||||
{
|
{
|
||||||
// default sensors present
|
control_sensors_present |=
|
||||||
control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT;
|
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
|
||||||
|
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||||
|
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
||||||
|
|
||||||
|
control_sensors_enabled |=
|
||||||
|
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
|
||||||
|
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||||
|
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
||||||
|
|
||||||
|
control_sensors_health |=
|
||||||
|
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
|
||||||
|
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||||
|
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
||||||
|
|
||||||
// first what sensors/controllers we have
|
// first what sensors/controllers we have
|
||||||
if (sub.g.compass_enabled) {
|
if (sub.g.compass_enabled) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||||
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||||
}
|
}
|
||||||
if (sub.ap.depth_sensor_present) {
|
if (sub.ap.depth_sensor_present) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||||
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||||
}
|
}
|
||||||
const AP_GPS &gps = AP::gps();
|
const AP_GPS &gps = AP::gps();
|
||||||
if (gps.status() > AP_GPS::NO_GPS) {
|
if (gps.status() > AP_GPS::NO_GPS) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
|
||||||
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
|
||||||
}
|
}
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
const OpticalFlow *optflow = AP::opticalflow();
|
const OpticalFlow *optflow = AP::opticalflow();
|
||||||
if (optflow && optflow->enabled()) {
|
if (optflow && optflow->enabled()) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||||
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// all present sensors enabled by default except altitude and position control and motors which we will set individually
|
control_sensors_present |=
|
||||||
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL &
|
MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL |
|
||||||
~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL &
|
MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
||||||
~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & ~MAV_SYS_STATUS_SENSOR_BATTERY);
|
|
||||||
|
|
||||||
switch (sub.control_mode) {
|
switch (sub.control_mode) {
|
||||||
case ALT_HOLD:
|
case ALT_HOLD:
|
||||||
@ -41,29 +53,16 @@ void GCS_Sub::update_sensor_status_flags()
|
|||||||
case SURFACE:
|
case SURFACE:
|
||||||
case POSHOLD:
|
case POSHOLD:
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||||
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
||||||
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; // check the internal barometer only
|
||||||
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
|
if (sub.sensor_health.depth) {
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
|
|
||||||
}
|
|
||||||
|
|
||||||
const AP_BattMonitor &battery = AP::battery();
|
|
||||||
if (battery.num_instances() > 0) {
|
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY;
|
|
||||||
}
|
|
||||||
|
|
||||||
// default to all healthy except baro, compass, gps and receiver which we set individually
|
|
||||||
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_RC_RECEIVER);
|
|
||||||
|
|
||||||
if (sub.sensor_health.depth) { // check the internal barometer only
|
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||||
}
|
}
|
||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
@ -80,23 +79,6 @@ void GCS_Sub::update_sensor_status_flags()
|
|||||||
}
|
}
|
||||||
#endif
|
#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 (!battery.healthy() || battery.has_failsafed()) {
|
|
||||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_BATTERY;
|
|
||||||
}
|
|
||||||
|
|
||||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
switch (terrain.status()) {
|
switch (terrain.status()) {
|
||||||
case AP_Terrain::TerrainStatusDisabled:
|
case AP_Terrain::TerrainStatusDisabled:
|
||||||
@ -124,12 +106,6 @@ void GCS_Sub::update_sensor_status_flags()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!sub.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);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// avoid building/linking Devo:
|
// avoid building/linking Devo:
|
||||||
|
@ -20,7 +20,7 @@ public:
|
|||||||
return _chan[ofs];
|
return _chan[ofs];
|
||||||
};
|
};
|
||||||
|
|
||||||
void update_sensor_status_flags() override;
|
void update_vehicle_sensor_status_flags() override;
|
||||||
|
|
||||||
uint32_t custom_mode() const override;
|
uint32_t custom_mode() const override;
|
||||||
MAV_TYPE frame_type() const override;
|
MAV_TYPE frame_type() const override;
|
||||||
|
Loading…
Reference in New Issue
Block a user