Browse Source

Fix max channel handling

QGC4.4
DonLakeFlyer 5 years ago
parent
commit
c16638d0a4
  1. 83
      src/AutoPilotPlugins/Common/RadioComponentController.cc
  2. 14
      src/AutoPilotPlugins/Common/RadioComponentController.h

83
src/AutoPilotPlugins/Common/RadioComponentController.cc

@ -98,10 +98,6 @@ RadioComponentController::RadioComponentController(void) @@ -98,10 +98,6 @@ RadioComponentController::RadioComponentController(void)
connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged);
_loadSettings();
// APM Stack has a bug where some RC params are missing. We need to know what these are so we can skip them if missing
// instead of popping missing param warnings.
_apmPossibleMissingRCChannelParams << 9 << 11 << 12 << 13 << 14;
_resetInternalCalibrationValues();
}
@ -217,7 +213,7 @@ void RadioComponentController::_setupCurrentState(void) @@ -217,7 +213,7 @@ void RadioComponentController::_setupCurrentState(void)
_statusText->setProperty("text", instructions);
_setHelpImage(helpImage);
_stickDetectChannel = _chanMax();
_stickDetectChannel = _chanMax;
_stickDetectSettleStarted = false;
_rcCalSaveCurrentValues();
@ -229,9 +225,7 @@ void RadioComponentController::_setupCurrentState(void) @@ -229,9 +225,7 @@ void RadioComponentController::_setupCurrentState(void)
/// Connected to Vehicle::rcChannelsChanged signal
void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels])
{
int maxChannel = std::min(channelCount, _chanMax());
for (int channel=0; channel<maxChannel; channel++) {
for (int channel=0; channel<channelCount; channel++) {
int channelValue = pwmValues[channel];
if (channelValue != -1) {
@ -392,7 +386,7 @@ void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, i @@ -392,7 +386,7 @@ void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, i
return;
}
if (_stickDetectChannel == _chanMax()) {
if (_stickDetectChannel == _chanMax) {
// We have not detected enough movement on a channel yet
if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) {
@ -439,7 +433,7 @@ void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int @@ -439,7 +433,7 @@ void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int
return;
}
if (_stickDetectChannel == _chanMax()) {
if (_stickDetectChannel == _chanMax) {
// Setup up to detect stick being pegged to extreme position
if (_rgChannelInfo[channel].reversed) {
if (value > _rcCalPWMCenterPoint + _rcCalMoveDelta) {
@ -486,7 +480,7 @@ void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, in @@ -486,7 +480,7 @@ void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, in
return;
}
if (_stickDetectChannel == _chanMax()) {
if (_stickDetectChannel == _chanMax) {
// Sticks have not yet moved close enough to center
if (abs(_rcCalPWMCenterPoint - value) < _rcCalRoughCenterDelta) {
@ -564,7 +558,7 @@ void RadioComponentController::_inputSwitchDetect(enum rcCalFunctions function, @@ -564,7 +558,7 @@ void RadioComponentController::_inputSwitchDetect(enum rcCalFunctions function,
void RadioComponentController::_resetInternalCalibrationValues(void)
{
// Set all raw channels to not reversed and center point values
for (int i=0; i<_chanMax(); i++) {
for (int i=0; i<_chanMax; i++) {
struct ChannelInfo* info = &_rgChannelInfo[i];
info->function = rcCalFunctionMax;
info->reversed = false;
@ -575,7 +569,7 @@ void RadioComponentController::_resetInternalCalibrationValues(void) @@ -575,7 +569,7 @@ void RadioComponentController::_resetInternalCalibrationValues(void)
// Initialize attitude function mapping to function channel not set
for (size_t i=0; i<rcCalFunctionMax; i++) {
_rgFunctionChannelMapping[i] = _chanMax();
_rgFunctionChannelMapping[i] = _chanMax;
}
_signalAllAttitudeValueChanges();
@ -586,13 +580,13 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) @@ -586,13 +580,13 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
{
// Initialize all function mappings to not set
for (int i=0; i<_chanMax(); i++) {
for (int i=0; i<_chanMax; i++) {
struct ChannelInfo* info = &_rgChannelInfo[i];
info->function = rcCalFunctionMax;
}
for (size_t i=0; i<rcCalFunctionMax; i++) {
_rgFunctionChannelMapping[i] = _chanMax();
_rgFunctionChannelMapping[i] = _chanMax;
}
// Pull parameters and update
@ -601,18 +595,15 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) @@ -601,18 +595,15 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
QString maxTpl("RC%1_MAX");
QString trimTpl("RC%1_TRIM");
for (int i = 0; i < _chanMax(); ++i) {
for (int i = 0; i < _chanMax; ++i) {
struct ChannelInfo* info = &_rgChannelInfo[i];
if (_px4Vehicle() && _apmPossibleMissingRCChannelParams.contains(i+1)) {
if (!parameterExists(FactSystem::defaultComponentId, minTpl.arg(i+1))) {
// Parameter is missing from this version of APM
info->rcTrim = 1500;
info->rcMin = 1100;
info->rcMax = 1900;
info->reversed = false;
continue;
}
if (!parameterExists(FactSystem::defaultComponentId, minTpl.arg(i+1))) {
info->rcTrim = 1500;
info->rcMin = 1100;
info->rcMax = 1900;
info->reversed = false;
continue;
}
Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1));
@ -642,7 +633,7 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) @@ -642,7 +633,7 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
if (paramFact) {
paramChannel = paramFact->rawValue().toInt();
if (paramChannel > 0 && paramChannel <= _chanMax()) {
if (paramChannel > 0 && paramChannel <= _chanMax) {
_rgFunctionChannelMapping[i] = paramChannel - 1;
_rgChannelInfo[paramChannel - 1].function = static_cast<rcCalFunctions>(i);
}
@ -661,7 +652,7 @@ void RadioComponentController::spektrumBindMode(int mode) @@ -661,7 +652,7 @@ void RadioComponentController::spektrumBindMode(int mode)
/// @brief Validates the current settings against the calibration rules resetting values as necessary.
void RadioComponentController::_validateCalibration(void)
{
for (int chan = 0; chan<_chanMax(); chan++) {
for (int chan = 0; chan<_chanMax; chan++) {
struct ChannelInfo* info = &_rgChannelInfo[chan];
if (chan < _chanCount) {
@ -725,12 +716,11 @@ void RadioComponentController::_writeCalibration(void) @@ -725,12 +716,11 @@ void RadioComponentController::_writeCalibration(void)
QString trimTpl("RC%1_TRIM");
// Note that the rc parameters are all float, so you must cast to float in order to get the right QVariant
for (int chan = 0; chan<_chanMax(); chan++) {
for (int chan = 0; chan<_chanMax; chan++) {
struct ChannelInfo* info = &_rgChannelInfo[chan];
int oneBasedChannel = chan + 1;
if (_px4Vehicle() && _apmPossibleMissingRCChannelParams.contains(chan+1) && !parameterExists(FactSystem::defaultComponentId, minTpl.arg(chan+1))) {
// RC parameters for this channel are missing from this version of APM
if (!parameterExists(FactSystem::defaultComponentId, minTpl.arg(chan+1))) {
continue;
}
@ -764,7 +754,7 @@ void RadioComponentController::_writeCalibration(void) @@ -764,7 +754,7 @@ void RadioComponentController::_writeCalibration(void)
// Write function mapping parameters
for (size_t i=0; i<rcCalFunctionMax; i++) {
int32_t paramChannel;
if (_rgFunctionChannelMapping[i] == _chanMax()) {
if (_rgFunctionChannelMapping[i] == _chanMax) {
// 0 signals no mapping
paramChannel = 0;
} else {
@ -844,7 +834,7 @@ void RadioComponentController::_stopCalibration(void) @@ -844,7 +834,7 @@ void RadioComponentController::_stopCalibration(void)
/// @brief Saves the current channel values, so that we can detect when the use moves an input.
void RadioComponentController::_rcCalSaveCurrentValues(void)
{
for (int i = 0; i < _chanMax(); i++) {
for (int i = 0; i < _chanMax; i++) {
_rcValueSave[i] = _rcRawValue[i];
qCDebug(RadioComponentControllerLog) << "_rcCalSaveCurrentValues channel:value" << i << _rcValueSave[i];
}
@ -918,7 +908,7 @@ int RadioComponentController::channelCount(void) @@ -918,7 +908,7 @@ int RadioComponentController::channelCount(void)
int RadioComponentController::rollChannelRCValue(void)
{
if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax()) {
if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax) {
return _rcRawValue[rcCalFunctionRoll];
} else {
return 1500;
@ -927,7 +917,7 @@ int RadioComponentController::rollChannelRCValue(void) @@ -927,7 +917,7 @@ int RadioComponentController::rollChannelRCValue(void)
int RadioComponentController::pitchChannelRCValue(void)
{
if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax()) {
if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax) {
return _rcRawValue[rcCalFunctionPitch];
} else {
return 1500;
@ -936,7 +926,7 @@ int RadioComponentController::pitchChannelRCValue(void) @@ -936,7 +926,7 @@ int RadioComponentController::pitchChannelRCValue(void)
int RadioComponentController::yawChannelRCValue(void)
{
if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax()) {
if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax) {
return _rcRawValue[rcCalFunctionYaw];
} else {
return 1500;
@ -945,7 +935,7 @@ int RadioComponentController::yawChannelRCValue(void) @@ -945,7 +935,7 @@ int RadioComponentController::yawChannelRCValue(void)
int RadioComponentController::throttleChannelRCValue(void)
{
if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax()) {
if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax) {
return _rcRawValue[rcCalFunctionThrottle];
} else {
return 1500;
@ -954,27 +944,27 @@ int RadioComponentController::throttleChannelRCValue(void) @@ -954,27 +944,27 @@ int RadioComponentController::throttleChannelRCValue(void)
bool RadioComponentController::rollChannelMapped(void)
{
return _rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax();
return _rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax;
}
bool RadioComponentController::pitchChannelMapped(void)
{
return _rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax();
return _rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax;
}
bool RadioComponentController::yawChannelMapped(void)
{
return _rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax();
return _rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax;
}
bool RadioComponentController::throttleChannelMapped(void)
{
return _rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax();
return _rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax;
}
bool RadioComponentController::rollChannelReversed(void)
{
if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax()) {
if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax) {
return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionRoll]].reversed;
} else {
return false;
@ -983,7 +973,7 @@ bool RadioComponentController::rollChannelReversed(void) @@ -983,7 +973,7 @@ bool RadioComponentController::rollChannelReversed(void)
bool RadioComponentController::pitchChannelReversed(void)
{
if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax()) {
if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax) {
return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionPitch]].reversed;
} else {
return false;
@ -992,7 +982,7 @@ bool RadioComponentController::pitchChannelReversed(void) @@ -992,7 +982,7 @@ bool RadioComponentController::pitchChannelReversed(void)
bool RadioComponentController::yawChannelReversed(void)
{
if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax()) {
if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax) {
return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionYaw]].reversed;
} else {
return false;
@ -1001,7 +991,7 @@ bool RadioComponentController::yawChannelReversed(void) @@ -1001,7 +991,7 @@ bool RadioComponentController::yawChannelReversed(void)
bool RadioComponentController::throttleChannelReversed(void)
{
if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax()) {
if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax) {
return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed;
} else {
return false;
@ -1047,11 +1037,6 @@ const struct RadioComponentController::FunctionInfo* RadioComponentController::_ @@ -1047,11 +1037,6 @@ const struct RadioComponentController::FunctionInfo* RadioComponentController::_
return _px4Vehicle() ? _rgFunctionInfoPX4 : _rgFunctionInfoAPM;
}
int RadioComponentController::_chanMax(void) const
{
return _px4Vehicle() ? _chanMaxPX4 : _chanMaxAPM;
}
bool RadioComponentController::_channelReversedParamValue(int channel)
{
Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _revParamFormat.arg(channel+1));

14
src/AutoPilotPlugins/Common/RadioComponentController.h

@ -232,8 +232,6 @@ private: @@ -232,8 +232,6 @@ private:
void _signalAllAttitudeValueChanges(void);
int _chanMax(void) const;
bool _channelReversedParamValue(int channel);
void _setChannelReversedParamValue(int channel, bool reversed);
@ -272,14 +270,10 @@ private: @@ -272,14 +270,10 @@ private:
static const int _attitudeControls = 5;
int _chanCount; ///< Number of actual rc channels available
static const int _chanMaxPX4 = 18; ///< Maximum number of supported rc channels, PX4 Firmware
static const int _chanMaxAPM = 14; ///< Maximum number of supported rc channels, APM firmware
static const int _chanMaxAny = 18; ///< Maximum number of support rc channels by this implementation
static const int _chanMax = 18; ///< Maximum number of support rc channels by this implementation
static const int _chanMinimum = 5; ///< Minimum numner of channels required to run
struct ChannelInfo _rgChannelInfo[_chanMaxAny]; ///< Information associated with each rc channel
QList<int> _apmPossibleMissingRCChannelParams; ///< List of possible missing RC*_* params for APM stack
struct ChannelInfo _rgChannelInfo[_chanMax]; ///< Information associated with each rc channel
enum rcCalStates _rcCalState; ///< Current calibration state
int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion
@ -302,9 +296,9 @@ private: @@ -302,9 +296,9 @@ private:
QString _revParamFormat;
bool _revParamIsBool;
int _rcValueSave[_chanMaxAny]; ///< Saved values prior to detecting channel movement
int _rcValueSave[_chanMax]; ///< Saved values prior to detecting channel movement
int _rcRawValue[_chanMaxAny]; ///< Current set of raw channel values
int _rcRawValue[_chanMax]; ///< Current set of raw channel values
int _stickDetectChannel;
int _stickDetectInitialValue;

Loading…
Cancel
Save