diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 569d3307574e21da449614bad0a4ac90d9261e04..fd76a799eb5297656e2e6368547f8e22dc04a906 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -3140,13 +3140,26 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x, float flow_comp_m_y, quint8 quality, float ground_distance) { + // FIXME: This needs to be updated for new mavlink_msg_hil_optical_flow_pack api + + Q_UNUSED(time_us); + Q_UNUSED(flow_x); + Q_UNUSED(flow_y); + Q_UNUSED(flow_comp_m_x); + Q_UNUSED(flow_comp_m_y); + Q_UNUSED(quality); + Q_UNUSED(ground_distance); + if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED) { +#if 0 mavlink_message_t msg; mavlink_msg_hil_optical_flow_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, - time_us, 0, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance); + time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance); + sendMessage(msg); lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds(); +#endif } else {