diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 549d564f48..1f653b80b9 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -2,9 +2,6 @@ #include "Tracker.h" -// default sensors are present and healthy: gyro, accelerometer, barometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control -#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE | 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) - /* * !!NOTE!! * @@ -84,11 +81,13 @@ void Tracker::send_extended_status1(mavlink_channel_t chan) battery_current = battery.current_amps() * 100; } + update_sensor_status_flags(); + mavlink_msg_sys_status_send( chan, - 0, - 0, - 0, + control_sensors_present, + control_sensors_enabled, + control_sensors_health, static_cast(scheduler.load_average() * 1000), battery.voltage() * 1000, // mV battery_current, // in 10mA units diff --git a/AntennaTracker/GCS_Mavlink.h b/AntennaTracker/GCS_Mavlink.h index fd5159aebf..2e5d8a1ae8 100644 --- a/AntennaTracker/GCS_Mavlink.h +++ b/AntennaTracker/GCS_Mavlink.h @@ -2,6 +2,9 @@ #include +// default sensors are present and healthy: gyro, accelerometer, barometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control +#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS) + class GCS_MAVLINK_Tracker : public GCS_MAVLINK { diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index c632fb82b2..8b12b2e07e 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -140,6 +140,11 @@ private: GCS_Tracker _gcs; // avoid using this; use gcs() GCS_Tracker &gcs() { return _gcs; } + // variables for extended status MAVLink messages + uint32_t control_sensors_present; + uint32_t control_sensors_enabled; + uint32_t control_sensors_health; + AP_BoardConfig BoardConfig; #if HAL_WITH_UAVCAN @@ -244,6 +249,7 @@ private: void accel_cal_update(void); void update_GPS(void); void handle_battery_failsafe(const char* type_str, const int8_t action); + void update_sensor_status_flags(); // servos.cpp void init_servos(); diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index c1ad696d26..6843d871b6 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -90,3 +90,68 @@ void Tracker::handle_battery_failsafe(const char* type_str, const int8_t action) // that is tracked before the tracker loses power to continue tracking it } +// update sensors and subsystems present, enabled and healthy flags for reporting to GCS +void Tracker::update_sensor_status_flags() +{ + // default sensors present + control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT; + + // first what sensors/controllers we have + if (g.compass_enabled) { + control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present + } + if (gps.status() > AP_GPS::NO_GPS) { + control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS; + } + if (DataFlash.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 and motor output which we will set individually + control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_LOGGING & + ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & + ~MAV_SYS_STATUS_SENSOR_BATTERY); + + if (DataFlash.logging_enabled()) { + control_sensors_enabled |= MAV_SYS_STATUS_LOGGING; + } + + // 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 (battery.num_instances() > 0) { + control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY; + } + + // default to all healthy except compass and gps which we set individually + control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS); + if (g.compass_enabled && compass.healthy(0) && 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 (!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 (DataFlash.logging_failed()) { + control_sensors_health &= ~MAV_SYS_STATUS_LOGGING; + } + if (!battery.healthy() || battery.has_failsafed()) { + control_sensors_enabled &= ~MAV_SYS_STATUS_SENSOR_BATTERY; + } + if (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); + } +}