ArduCopter: include precision landing sensor in mavlink system status

Set MAV_SYS_STATUS_SENSOR_VISION_POSITION bit in onboard_control_sensors_present, onboard_control_sensors_enabled and onboard_control_sensors_health based on the status of precision landing sensor.
This commit is contained in:
Derek Ma 2016-01-07 10:49:49 -08:00 committed by Randy Mackay
parent 25de3c74c5
commit 3751dbef91
1 changed files with 10 additions and 0 deletions

View File

@ -143,6 +143,11 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
if (optflow.enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif
#if PRECISION_LANDING == ENABLED
if (precland.enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
}
#endif
if (ap.rc_receiver_present) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
@ -194,6 +199,11 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
if (optflow.healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif
#if PRECISION_LANDING == ENABLED
if (precland.healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
}
#endif
if (ap.rc_receiver_present && !failsafe.radio) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;