Copter: report RC receiver health to GCS

This commit is contained in:
Randy Mackay 2013-10-21 22:39:25 +09:00
parent 0049351f2f
commit d86ac9041e
3 changed files with 15 additions and 2 deletions

View File

@ -395,6 +395,8 @@ static union {
uint8_t yaw_stopped : 1; // 16 // Used to manage the Yaw hold capabilities
uint8_t disable_stab_rate_limit : 1; // 17 // disables limits rate request from the stability controller
uint8_t rc_receiver_present : 1; // 18 // true if we have an rc receiver present (i.e. if we've ever received an update
};
uint32_t value;
} ap;

View File

@ -156,6 +156,9 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif
if (ap.rc_receiver_present) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
}
// all present sensors enabled by default except altitude and position control which we will set individually
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL & ~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL);
@ -180,14 +183,17 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
break;
}
// 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);
// default to all healthy except compass, gps and receiver which we set individually
control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS & ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
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_GPS && !gps_glitch.glitching()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
if (ap.rc_receiver_present && !failsafe.radio) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
}
int16_t battery_current = -1;
int8_t battery_remaining = -1;

View File

@ -130,6 +130,11 @@ static void read_radio()
g.rc_6.set_pwm(periods[5]);
g.rc_7.set_pwm(periods[6]);
g.rc_8.set_pwm(periods[7]);
// flag we must have an rc receiver attached
if (!failsafe.rc_override_active) {
ap.rc_receiver_present = true;
}
}else{
uint32_t elapsed = millis() - last_update;
// turn on throttle failsafe if no update from ppm encoder for 2 seconds