From 3751dbef916aba016a1ca4c046fa712c8c7c6e24 Mon Sep 17 00:00:00 2001 From: Derek Ma Date: Thu, 7 Jan 2016 10:49:49 -0800 Subject: [PATCH] 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. --- ArduCopter/GCS_Mavlink.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 2c66509087..fe56953ea9 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -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;