8#include <QtCore/QSettings>
20 _calDefaultMinValue = 1000;
21 _calDefaultMaxValue = 2000;
22 _calCenterPoint= ((_calDefaultMaxValue - _calDefaultMinValue) / 2.0f) + _calDefaultMinValue;
23 _calRoughCenterDelta = 50;
27 int valueRange = _calDefaultMaxValue - _calDefaultMinValue;
28 _calValidMinValue = _calDefaultMinValue + (valueRange * 0.3f);
29 _calValidMaxValue = _calDefaultMaxValue - (valueRange * 0.3f);
34 _revParamFormat =
"RC%1_REVERSED";
35 _revParamIsBool =
true;
38 _revParamFormat =
"RC%1_REV";
39 _revParamIsBool =
false;
58 RemoteControlCalibrationController::start();
73bool RadioComponentController::_channelReversedParamValue(
int channel)
77 if (_revParamIsBool) {
78 return paramFact->rawValue().toBool();
81 float floatReversed = paramFact->rawValue().toFloat(&convertOk);
86 return floatReversed == -1.0f;
93void RadioComponentController::_setChannelReversedParamValue(
int channel,
bool reversed)
97 if (_revParamIsBool) {
98 paramFact->setRawValue(reversed);
100 paramFact->setRawValue(reversed ? -1.0f : 1.0f);
105void RadioComponentController::_saveStoredCalibrationValues()
114 const QString minTpl(
"RC%1_MIN");
115 const QString maxTpl(
"RC%1_MAX");
116 const QString trimTpl(
"RC%1_TRIM");
119 for (
int chan = 0; chan<
_chanMax; chan++) {
121 const int oneBasedChannel = chan + 1;
129 paramFact->setRawValue(
static_cast<float>(info->channelTrim));
133 paramFact->setRawValue(
static_cast<float>(info->channelMin));
137 paramFact->setRawValue(
static_cast<float>(info->channelMax));
146 reversed = info->channelReversed;
148 reversed = !info->channelReversed;
150 _setChannelReversedParamValue(chan, reversed);
155 for (
size_t stickFunctionIndex = 0; stickFunctionIndex < stickFunctionMaxRadio; stickFunctionIndex++) {
156 int32_t paramChannel;
165 QString paramName = _stickFunctionToParamName(
static_cast<StickFunction
>(stickFunctionIndex));
168 if (paramFact && paramFact->rawValue().toInt() != paramChannel) {
171 paramFact->setRawValue(paramChannel);
185 _readStoredCalibrationValues();
188void RadioComponentController::_readStoredCalibrationValues()
192 for (
int i = 0; i <
_chanMax; i++) {
197 for (
size_t i = 0; i < stickFunctionMaxRadio; i++) {
203 const QString minTpl(
"RC%1_MIN");
204 const QString maxTpl(
"RC%1_MAX");
205 const QString trimTpl(
"RC%1_TRIM");
207 for (
int i = 0; i <
_chanMax; ++i) {
212 info->channelMin = 1100;
213 info->channelMax = 1900;
214 info->channelReversed =
false;
220 info->channelTrim = paramFact->rawValue().toInt();
225 info->channelMin = paramFact->rawValue().toInt();
233 info->channelReversed = _channelReversedParamValue(i);
236 for (
int i=0; i<stickFunctionMaxRadio; i++) {
237 int32_t paramChannel;
239 QString paramName = _stickFunctionToParamName(
static_cast<StickFunction
>(i));
242 paramChannel = paramFact->rawValue().toInt();
244 if (paramChannel > 0 && paramChannel <=
_chanMax) {
254QString RadioComponentController::_stickFunctionToParamName(RemoteControlCalibrationController::StickFunction function)
const
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" },
263 static const QHash<StickFunction, QString> rgStickFunctionParamsAPM({
264 { stickFunctionRoll,
"RCMAP_ROLL" },
265 { stickFunctionPitch,
"RCMAP_PITCH" },
266 { stickFunctionYaw,
"RCMAP_YAW" },
267 { stickFunctionThrottle,
"RCMAP_THROTTLE" },
270 const auto &rgStickFunctionParams =
_vehicle->
px4Firmware() ? rgStickFunctionParamsPX4 : rgStickFunctionParamsAPM;
272 if (!rgStickFunctionParams.contains(function)) {
273 qCWarning(RadioComponentControllerLog) <<
"Internal Error: Invalid stick function";
277 return rgStickFunctionParams.value(function);
#define QGC_LOGGING_CATEGORY(name, categoryStr)
A Fact is used to hold a single value within the system.
static constexpr int defaultComponentId
Controller class for RC Transmitter calibration.
void start() final override
~RadioComponentController()
void throttleReversedCalFailure()
Signalled to indicate cal failure due to reversed throttle.
void spektrumBindMode(int mode)
Abstract base class for calibrating RC and Joystick controller.
void rawChannelValuesChanged(QVector< int > channelValues)
void _validateAndAdjustCalibrationValues()
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.
void _signalAllAttitudeValueChanges()
MAV_TYPE vehicleType() const
void pairRX(int rxType, int rxSubType)
void stopCalibration(bool showError)
void rcChannelsChanged(QVector< int > channelValues)
int channelTrim
Trim position (usually center for sticks)
enum StickFunction stickFunction
Function mapped to this channel, stickFunctionMax for none.