From ab62105afe511717add78ef64a219ba31c61615b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 3 Jan 2015 15:53:49 +1100 Subject: [PATCH] Copter: use common send_opticalflow() --- ArduCopter/GCS_Mavlink.pde | 28 +--------------------------- ArduCopter/config.h | 2 +- 2 files changed, 2 insertions(+), 28 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index f856fd4410..b510380fa9 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -441,32 +441,6 @@ static void NOINLINE send_rangefinder(mavlink_channel_t chan) } #endif -#if OPTFLOW == ENABLED -static void NOINLINE send_opticalflow(mavlink_channel_t chan) -{ - // exit immediately if no optical flow sensor or not healthy - if (!optflow.healthy()) { - return; - } - - // get rates from sensor - const Vector2f &flowRate = optflow.flowRate(); - const Vector2f &bodyRate = optflow.bodyRate(); - - // populate and send message - mavlink_msg_optical_flow_send( - chan, - millis(), - 0, // sensor id is zero - flowRate.x, - flowRate.y, - bodyRate.x, - bodyRate.y, - optflow.quality(), - 0); // ground distance (in meters) set to zero -} -#endif // OPTFLOW == ENABLED - static void NOINLINE send_statustext(mavlink_channel_t chan) { mavlink_statustext_t *s = &gcs[chan-MAVLINK_COMM_0].pending_status; @@ -674,7 +648,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) case MSG_OPTICAL_FLOW: #if OPTFLOW == ENABLED CHECK_PAYLOAD_SIZE(OPTICAL_FLOW); - send_opticalflow(chan); + gcs[chan-MAVLINK_COMM_0].send_opticalflow(ahrs, optflow); #endif break; diff --git a/ArduCopter/config.h b/ArduCopter/config.h index dfc51baf49..f9edb93b68 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -388,7 +388,7 @@ ////////////////////////////////////////////////////////////////////////////// // OPTICAL_FLOW #ifndef OPTFLOW - #if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 + #if AP_AHRS_NAVEKF_AVAILABLE # define OPTFLOW ENABLED #else # define OPTFLOW DISABLED