From 88b9528b54cf06e0872b105bb659f08b06767892 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Mon, 30 Dec 2013 00:29:32 +0100 Subject: [PATCH] Build fix and adjust array size --- src/ui/MAVLinkDecoder.cc | 2 +- src/ui/QGCPX4VehicleConfig.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc index 2398b72..4a753ff 100644 --- a/src/ui/MAVLinkDecoder.cc +++ b/src/ui/MAVLinkDecoder.cc @@ -261,7 +261,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 { // XXX this is really ugly, but we do not know a better way to do this mavlink_servo_output_raw_t servo; - mavlink_msg_rc_channels_scaled_decode(msg, &servo); + mavlink_msg_servo_output_raw_decode(msg, &servo); name = name.arg(messageInfo[msgid].name).arg(fieldName); name.prepend(QString("port%1_").arg(servo.port)); } diff --git a/src/ui/QGCPX4VehicleConfig.h b/src/ui/QGCPX4VehicleConfig.h index 07b1888..10e2956 100644 --- a/src/ui/QGCPX4VehicleConfig.h +++ b/src/ui/QGCPX4VehicleConfig.h @@ -278,7 +278,7 @@ protected: UASInterface* mav; ///< The current MAV QGCUASParamManagerInterface* paramMgr; ///< params mgr for the mav static const unsigned int chanMax = 18; ///< Maximum number of channels - static const unsigned int chanMappedMax = 16; ///< Maximum number of mapped channels (can be higher than input channel count) + static const unsigned int chanMappedMax = 18; ///< Maximum number of mapped channels (can be higher than input channel count) unsigned int chanCount; ///< Actual channels float rcMin[chanMax]; ///< Minimum values float rcMax[chanMax]; ///< Maximum values