Plane: mavlink ext status to use SYS_STATUS_SENSOR enum

This commit is contained in:
Randy Mackay 2013-10-04 12:33:31 +09:00
parent 09de917b27
commit 6e2b1093fc
1 changed files with 34 additions and 41 deletions

View File

@ -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, 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)
// use this to prevent recursion during sensor init
static bool in_mavlink_delay;
@ -128,60 +131,52 @@ static NOINLINE void send_fence_status(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
}
if (airspeed.enabled() && airspeed.use()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
}
control_sensors_present |= (1<<3); // absolute pressure sensor present
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) {
control_sensors_present |= (1<<5); // GPS present
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_Z_ALTITUDE_CONTROL & ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL & ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS);
switch (control_mode) {
case MANUAL:
break;
case ACRO:
control_sensors_enabled |= (1<<10); // 3D angular rate control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control
break;
case STABILIZE:
case FLY_BY_WIRE_A:
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 FLY_BY_WIRE_B:
case CRUISE:
control_sensors_enabled |= (1<<10); // 3D angular rate control
control_sensors_enabled |= (1<<11); // attitude stabilisation
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_MOTOR_OUTPUTS; // motor control
break;
case TRAINING:
if (!training_manual_roll || !training_manual_pitch) {
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;
@ -190,27 +185,25 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
case LOITER:
case GUIDED:
case CIRCLE:
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_Z_ALTITUDE_CONTROL; // altitude control
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 (!ahrs.use_compass()) {
control_sensors_health &= ~(1<<2); // compass not being used
// 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 (g_gps != NULL && g_gps->status() <= GPS::NO_FIX) {
control_sensors_health &= ~(1<<5); // GPS unhealthy
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
int16_t battery_current = -1;