QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RadioComponentController.cc
Go to the documentation of this file.
2#include "Fact.h"
3#include "ParameterManager.h"
4#include "QGCApplication.h"
6#include "Vehicle.h"
7
8#include <QtCore/QSettings>
9
10QGC_LOGGING_CATEGORY(RadioComponentControllerLog, "AutoPilotPlugins.RadioComponentController")
11QGC_LOGGING_CATEGORY(RadioComponentControllerVerboseLog, "AutoPilotPlugins.RadioComponentController:verbose")
12
15{
16 // qCDebug(RadioComponentControllerLog) << Q_FUNC_INFO << this;
17
18 // Channels values are in PWM
19
20 _calDefaultMinValue = 1000;
21 _calDefaultMaxValue = 2000;
22 _calCenterPoint= ((_calDefaultMaxValue - _calDefaultMinValue) / 2.0f) + _calDefaultMinValue;
23 _calRoughCenterDelta = 50;
24 _calMoveDelta = 300;
25 _calSettleDelta = 20;
26
27 int valueRange = _calDefaultMaxValue - _calDefaultMinValue;
28 _calValidMinValue = _calDefaultMinValue + (valueRange * 0.3f);
29 _calValidMaxValue = _calDefaultMaxValue - (valueRange * 0.3f);
30
31 // Deal with parameter differences between PX4 and Ardupilot
32 if (parameterExists(ParameterManager::defaultComponentId, QStringLiteral("RC1_REVERSED"))) {
33 // Newer ardupilot firmwares have a different reverse param naming scheme and value scheme
34 _revParamFormat = "RC%1_REVERSED";
35 _revParamIsBool = true; // param value is boolean 0/1 for reversed or not
36 } else {
37 // Older ardupilot firmwares share the same naming convention as PX4
38 _revParamFormat = "RC%1_REV";
39 _revParamIsBool = false; // param value if -1 indicates reversed
40 }
41
42 // Let the mav known we are starting calibration. This should turn off motors and so forth.
43 _vehicle->startCalibration(QGCMAVLink::CalibrationRadio);
44}
45
47{
48 // qCDebug(RadioComponentControllerLog) << Q_FUNC_INFO << this;
49 if (_vehicle) {
50 // Only PX4 is known to support this command in all versions. For other firmware which may or may not
51 // support this we don't show errors on failure.
52 _vehicle->stopCalibration(_vehicle->px4Firmware() ? true : false /* showError */);
53 }
54}
55
57{
58 RemoteControlCalibrationController::start();
60
61}
62
64{
65 _vehicle->pairRX(RC_TYPE_SPEKTRUM, mode);
66}
67
69{
70 _vehicle->pairRX(RC_TYPE_CRSF, 0);
71}
72
73bool RadioComponentController::_channelReversedParamValue(int channel)
74{
75 Fact *const paramFact = getParameterFact(ParameterManager::defaultComponentId, _revParamFormat.arg(channel+1));
76 if (paramFact) {
77 if (_revParamIsBool) {
78 return paramFact->rawValue().toBool();
79 } else {
80 bool convertOk;
81 float floatReversed = paramFact->rawValue().toFloat(&convertOk);
82 if (!convertOk) {
83 floatReversed = 1.0f;
84 }
85
86 return floatReversed == -1.0f;
87 }
88 }
89
90 return false;
91}
92
93void RadioComponentController::_setChannelReversedParamValue(int channel, bool reversed)
94{
95 Fact *const paramFact = getParameterFact(ParameterManager::defaultComponentId, _revParamFormat.arg(channel+1));
96 if (paramFact) {
97 if (_revParamIsBool) {
98 paramFact->setRawValue(reversed);
99 } else {
100 paramFact->setRawValue(reversed ? -1.0f : 1.0f);
101 }
102 }
103}
104
105void RadioComponentController::_saveStoredCalibrationValues()
106{
107 if (!_vehicle->px4Firmware() && ((_vehicle->vehicleType() == MAV_TYPE_HELICOPTER) || _vehicle->multiRotor()) && _rgChannelInfo[_rgFunctionChannelMapping[stickFunctionThrottle]].channelReversed) {
108 // A reversed throttle could lead to dangerous power up issues if the firmware doesn't handle it absolutely correctly in all places.
109 // So in this case fail the calibration for anything other than PX4 which is known to be able to handle this correctly.
111 } else {
113
114 const QString minTpl("RC%1_MIN");
115 const QString maxTpl("RC%1_MAX");
116 const QString trimTpl("RC%1_TRIM");
117
118 // Note that the rc parameters are all float, so you must cast to float in order to get the right QVariant
119 for (int chan = 0; chan<_chanMax; chan++) {
120 ChannelInfo *const info = &_rgChannelInfo[chan];
121 const int oneBasedChannel = chan + 1;
122
123 if (!parameterExists(ParameterManager::defaultComponentId, minTpl.arg(chan+1))) {
124 continue;
125 }
126
127 Fact* paramFact = getParameterFact(ParameterManager::defaultComponentId, trimTpl.arg(oneBasedChannel));
128 if (paramFact) {
129 paramFact->setRawValue(static_cast<float>(info->channelTrim));
130 }
131 paramFact = getParameterFact(ParameterManager::defaultComponentId, minTpl.arg(oneBasedChannel));
132 if (paramFact) {
133 paramFact->setRawValue(static_cast<float>(info->channelMin));
134 }
135 paramFact = getParameterFact(ParameterManager::defaultComponentId, maxTpl.arg(oneBasedChannel));
136 if (paramFact) {
137 paramFact->setRawValue(static_cast<float>(info->channelMax));
138 }
139
140 // For multi-rotor we can determine reverse setting during radio cal. For anything other than multi-rotor, servo installation
141 // may affect channel reversing so we can't automatically determine it. This is ok for PX4 given how it uses mixers, but not for ArduPilot.
143 // APM multi-rotor has a backwards interpretation of "reversed" on the Pitch control. So be careful.
144 bool reversed;
145 if (_vehicle->px4Firmware() || info->stickFunction != stickFunctionPitch) {
146 reversed = info->channelReversed;
147 } else {
148 reversed = !info->channelReversed;
149 }
150 _setChannelReversedParamValue(chan, reversed);
151 }
152 }
153
154 // Write function mapping parameters
155 for (size_t stickFunctionIndex = 0; stickFunctionIndex < stickFunctionMaxRadio; stickFunctionIndex++) {
156 int32_t paramChannel;
157 if (_rgFunctionChannelMapping[stickFunctionIndex] == _chanMax) {
158 // 0 signals no mapping
159 paramChannel = 0;
160 } else {
161 // Note that the channel value is 1-based
162 paramChannel = _rgFunctionChannelMapping[stickFunctionIndex] + 1;
163 }
164
165 QString paramName = _stickFunctionToParamName(static_cast<StickFunction>(stickFunctionIndex));
166 Fact* paramFact = getParameterFact(ParameterManager::defaultComponentId, paramName);
167
168 if (paramFact && paramFact->rawValue().toInt() != paramChannel) {
169 paramFact = getParameterFact(ParameterManager::defaultComponentId, paramName);
170 if (paramFact) {
171 paramFact->setRawValue(paramChannel);
172 }
173 }
174 }
175 }
176
177 if (_vehicle->px4Firmware()) {
178 // If the RC_CHAN_COUNT parameter is available write the channel count
179 if (parameterExists(ParameterManager::defaultComponentId, QStringLiteral("RC_CHAN_CNT"))) {
180 getParameterFact(ParameterManager::defaultComponentId, QStringLiteral("RC_CHAN_CNT"))->setRawValue(_chanCount);
181 }
182 }
183
184 // Read back since validation may have changed values
185 _readStoredCalibrationValues();
186}
187
188void RadioComponentController::_readStoredCalibrationValues()
189{
190 // Initialize all function mappings to not set
191
192 for (int i = 0; i < _chanMax; i++) {
193 ChannelInfo *const info = &_rgChannelInfo[i];
194 info->stickFunction = stickFunctionMaxRadio;
195 }
196
197 for (size_t i = 0; i < stickFunctionMaxRadio; i++) {
199 }
200
201 // Pull parameters and update
202
203 const QString minTpl("RC%1_MIN");
204 const QString maxTpl("RC%1_MAX");
205 const QString trimTpl("RC%1_TRIM");
206
207 for (int i = 0; i < _chanMax; ++i) {
208 ChannelInfo *const info = &_rgChannelInfo[i];
209
210 if (!parameterExists(ParameterManager::defaultComponentId, minTpl.arg(i+1))) {
211 info->channelTrim = 1500;
212 info->channelMin = 1100;
213 info->channelMax = 1900;
214 info->channelReversed = false;
215 continue;
216 }
217
218 Fact *paramFact = getParameterFact(ParameterManager::defaultComponentId, trimTpl.arg(i+1));
219 if (paramFact) {
220 info->channelTrim = paramFact->rawValue().toInt();
221 }
222
223 paramFact = getParameterFact(ParameterManager::defaultComponentId, minTpl.arg(i+1));
224 if (paramFact) {
225 info->channelMin = paramFact->rawValue().toInt();
226 }
227
228 paramFact = getParameterFact(ParameterManager::defaultComponentId, maxTpl.arg(i+1));
229 if (paramFact) {
230 info->channelMax = getParameterFact(ParameterManager::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt();
231 }
232
233 info->channelReversed = _channelReversedParamValue(i);
234 }
235
236 for (int i=0; i<stickFunctionMaxRadio; i++) {
237 int32_t paramChannel;
238
239 QString paramName = _stickFunctionToParamName(static_cast<StickFunction>(i));
240 Fact *const paramFact = getParameterFact(ParameterManager::defaultComponentId, paramName);
241 if (paramFact) {
242 paramChannel = paramFact->rawValue().toInt();
243
244 if (paramChannel > 0 && paramChannel <= _chanMax) {
245 _rgFunctionChannelMapping[i] = paramChannel - 1;
246 _rgChannelInfo[paramChannel - 1].stickFunction = static_cast<StickFunction>(i);
247 }
248 }
249 }
250
252}
253
254QString RadioComponentController::_stickFunctionToParamName(RemoteControlCalibrationController::StickFunction function) const
255{
256 static const QHash<StickFunction, QString> rgStickFunctionParamsPX4({
257 { stickFunctionRoll, "RC_MAP_ROLL" },
258 { stickFunctionPitch, "RC_MAP_PITCH" },
259 { stickFunctionYaw, "RC_MAP_YAW" },
260 { stickFunctionThrottle, "RC_MAP_THROTTLE" },
261 });
262
263 static const QHash<StickFunction, QString> rgStickFunctionParamsAPM({
264 { stickFunctionRoll, "RCMAP_ROLL" },
265 { stickFunctionPitch, "RCMAP_PITCH" },
266 { stickFunctionYaw, "RCMAP_YAW" },
267 { stickFunctionThrottle, "RCMAP_THROTTLE" },
268 });
269
270 const auto &rgStickFunctionParams = _vehicle->px4Firmware() ? rgStickFunctionParamsPX4 : rgStickFunctionParamsAPM;
271
272 if (!rgStickFunctionParams.contains(function)) {
273 qCWarning(RadioComponentControllerLog) << "Internal Error: Invalid stick function";
274 return QString();
275 }
276
277 return rgStickFunctionParams.value(function);
278}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
A Fact is used to hold a single value within the system.
Definition Fact.h:19
static constexpr int defaultComponentId
Controller class for RC Transmitter calibration.
void throttleReversedCalFailure()
Signalled to indicate cal failure due to reversed throttle.
Abstract base class for calibrating RC and Joystick controller.
void rawChannelValuesChanged(QVector< int > channelValues)
static constexpr int _chanMax
A set of information associated with a radio channel.
ChannelInfo _rgChannelInfo[_chanMax]
Information associated with each rc channel.
int _rgFunctionChannelMapping[stickFunctionMax]
Maps from StickFunction to channel index. _chanMax indicates channel not set for this function.
int _chanCount
Number of actual rc channels available.
bool px4Firmware() const
Definition Vehicle.h:495
bool multiRotor() const
Definition Vehicle.cc:1864
MAV_TYPE vehicleType() const
Definition Vehicle.h:428
void pairRX(int rxType, int rxSubType)
Definition Vehicle.cc:4090
void stopCalibration(bool showError)
Definition Vehicle.cc:3298
void rcChannelsChanged(QVector< int > channelValues)
int channelTrim
Trim position (usually center for sticks)
enum StickFunction stickFunction
Function mapped to this channel, stickFunctionMax for none.