Browse Source

Build fix and adjust array size

QGC4.4
Lorenz Meier 11 years ago
parent
commit
88b9528b54
  1. 2
      src/ui/MAVLinkDecoder.cc
  2. 2
      src/ui/QGCPX4VehicleConfig.h

2
src/ui/MAVLinkDecoder.cc

@ -261,7 +261,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 @@ -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));
}

2
src/ui/QGCPX4VehicleConfig.h

@ -278,7 +278,7 @@ protected: @@ -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

Loading…
Cancel
Save