diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index 7375cddfdf..a4aa65e151 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -1,5 +1,8 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +// default sensors are present and healthy: gyro, accelerometer, 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_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS) + // use this to prevent recursion during sensor init static bool in_mavlink_delay; @@ -104,34 +107,23 @@ static NOINLINE void send_attitude(mavlink_channel_t chan) static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops) { - uint32_t control_sensors_present = 0; + uint32_t control_sensors_present; uint32_t control_sensors_enabled; uint32_t control_sensors_health; + // default sensors present + control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT; + // first what sensors/controllers we have - control_sensors_present |= (1<<0); // 3D gyro present - control_sensors_present |= (1<<1); // 3D accelerometer present if (g.compass_enabled) { - control_sensors_present |= (1<<2); // compass present + control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present } - control_sensors_present |= (1<<3); // absolute pressure sensor present - if (g_gps != NULL && g_gps->status() >= GPS::NO_FIX) { - control_sensors_present |= (1<<5); // GPS present + if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) { + control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS; } - control_sensors_present |= (1<<10); // 3D angular rate control - control_sensors_present |= (1<<11); // attitude stabilisation - control_sensors_present |= (1<<12); // yaw position - control_sensors_present |= (1<<13); // altitude control - control_sensors_present |= (1<<14); // X/Y position control - control_sensors_present |= (1<<15); // motor control - // now what sensors/controllers are enabled - - // first the sensors - control_sensors_enabled = control_sensors_present & 0x1FF; - - // now the controllers - control_sensors_enabled = control_sensors_present & 0x1FF; + // 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_SENSOR_ANGULAR_RATE_CONTROL & ~MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION & ~MAV_SYS_STATUS_SENSOR_YAW_POSITION & ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL & ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS); switch (control_mode) { case MANUAL: @@ -140,33 +132,31 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack case LEARNING: case STEERING: - control_sensors_enabled |= (1<<10); // 3D angular rate control - control_sensors_enabled |= (1<<11); // attitude stabilisation + 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 GUIDED: - control_sensors_enabled |= (1<<10); // 3D angular rate control - control_sensors_enabled |= (1<<11); // attitude stabilisation - control_sensors_enabled |= (1<<12); // yaw position - control_sensors_enabled |= (1<<13); // altitude control - control_sensors_enabled |= (1<<14); // X/Y position control - control_sensors_enabled |= (1<<15); // motor control + 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_XY_POSITION_CONTROL; // X/Y position control + control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; // motor control break; case INITIALISING: break; } - // at the moment all sensors/controllers are assumed healthy - control_sensors_health = control_sensors_present; - - if (!compass.healthy) { - control_sensors_health &= ~(1<<2); // compass + // 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 && ahrs.use_compass()) { + control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG; } - if (!compass.use_for_yaw()) { - control_sensors_enabled &= ~(1<<2); // compass + if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) { + control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS; } int16_t battery_current = -1;