Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
a03e816a
Commit
a03e816a
authored
Mar 15, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Bug fix: Flight modes trashed by calibration
Also converted to new logging category
parent
c8f1e925
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
86 additions
and
50 deletions
+86
-50
PX4RCCalibrationTest.cc
src/qgcunittest/PX4RCCalibrationTest.cc
+55
-27
PX4RCCalibrationTest.h
src/qgcunittest/PX4RCCalibrationTest.h
+4
-2
PX4RCCalibration.cc
src/ui/px4_configuration/PX4RCCalibration.cc
+24
-21
PX4RCCalibration.h
src/ui/px4_configuration/PX4RCCalibration.h
+3
-0
No files found.
src/qgcunittest/PX4RCCalibrationTest.cc
View file @
a03e816a
...
...
@@ -31,6 +31,7 @@
/// @author Don Gagne <don@thegagnes.com>
UT_REGISTER_TEST
(
PX4RCCalibrationTest
)
QGC_LOGGING_CATEGORY
(
PX4RCCalibrationTestLog
,
"PX4RCCalibrationTestLog"
)
// This will check for the wizard buttons being enabled of disabled according to the mask you pass in.
// We use a macro instead of a method so that we get better line number reporting on failure.
...
...
@@ -39,7 +40,7 @@ UT_REGISTER_TEST(PX4RCCalibrationTest)
if (_nextButton->isEnabled() != !!((mask) & nextButtonMask) || \
_skipButton->isEnabled() != !!((mask) & skipButtonMask) || \
_cancelButton->isEnabled() != !!((mask) & cancelButtonMask) ) { \
q
Debug(
) << _statusLabel->text(); \
q
CDebug(PX4RCCalibrationTestLog
) << _statusLabel->text(); \
} \
QCOMPARE(_nextButton->isEnabled(), !!((mask) & nextButtonMask)); \
QCOMPARE(_skipButton->isEnabled(), !!((mask) & skipButtonMask)); \
...
...
@@ -66,10 +67,6 @@ const int PX4RCCalibrationTest::_testMinValue = PX4RCCalibration::_rcCalPWMDefau
const
int
PX4RCCalibrationTest
::
_testMaxValue
=
PX4RCCalibration
::
_rcCalPWMDefaultMaxValue
-
10
;
const
int
PX4RCCalibrationTest
::
_testCenterValue
=
PX4RCCalibrationTest
::
_testMinValue
+
((
PX4RCCalibrationTest
::
_testMaxValue
-
PX4RCCalibrationTest
::
_testMinValue
)
/
2
);
/// @brief Maps from function index to channel index. -1 signals no mapping. Channel indices are offset 1 from function index
/// to catch bugs where function index is incorrectly used as channel index.
const
int
PX4RCCalibrationTest
::
_rgFunctionChannelMap
[
PX4RCCalibration
::
rcCalFunctionMax
]
=
{
1
,
2
,
3
,
4
,
-
1
,
-
1
,
-
1
,
-
1
,
9
,
10
,
11
};
const
struct
PX4RCCalibrationTest
::
ChannelSettings
PX4RCCalibrationTest
::
_rgChannelSettings
[
PX4RCCalibrationTest
::
_availableChannels
]
=
{
// Function Min Max # Reversed
...
...
@@ -145,19 +142,6 @@ PX4RCCalibrationTest::PX4RCCalibrationTest(void) :
{
}
/// @brief Called one time before any test cases are run.
void
PX4RCCalibrationTest
::
initTestCase
(
void
)
{
// Validate that our function to channel mapping is still correct.
for
(
int
function
=
0
;
function
<
PX4RCCalibration
::
rcCalFunctionMax
;
function
++
)
{
int
chanIndex
=
_rgFunctionChannelMap
[
function
];
if
(
chanIndex
!=
-
1
)
{
Q_ASSERT
(
_rgChannelSettings
[
chanIndex
].
function
==
function
);
Q_ASSERT
(
_rgChannelSettingsValidate
[
chanIndex
].
function
==
function
);
}
}
}
void
PX4RCCalibrationTest
::
init
(
void
)
{
UnitTest
::
init
();
...
...
@@ -252,7 +236,7 @@ void PX4RCCalibrationTest::_minRCChannels_test(void)
// Only available channels should have visible widget. A ui update cycle needs to have passed so we wait a little.
QTest::qWait(PX4RCCalibration::_updateInterval * 2);
for (int chanWidget=0; chanWidget<PX4RCCalibration::_chanMax; chanWidget++) {
//qDebug(
) << _rgValueWidget[chanWidget]->objectName() << chanWidget << chan;
qCDebug(PX4RCCalibrationTestLog
) << _rgValueWidget[chanWidget]->objectName() << chanWidget << chan;
QCOMPARE(_rgValueWidget[chanWidget]->isVisible(), !!(chanWidget <= chan));
}
#endif
...
...
@@ -272,7 +256,7 @@ void PX4RCCalibrationTest::_beginCalibration(void)
void
PX4RCCalibrationTest
::
_stickMoveWaitForSettle
(
int
channel
,
int
value
)
{
//qDebug(
) << "_stickMoveWaitForSettle channel:value" << channel << value;
qCDebug
(
PX4RCCalibrationTestLog
)
<<
"_stickMoveWaitForSettle channel:value"
<<
channel
<<
value
;
// Move the stick, this will initialized the settle checker
_mockUAS
->
emitRemoteControlChannelRawChanged
(
channel
,
value
);
...
...
@@ -290,7 +274,7 @@ void PX4RCCalibrationTest::_stickMoveWaitForSettle(int channel, int value)
void
PX4RCCalibrationTest
::
_stickMoveAutoStep
(
const
char
*
functionStr
,
enum
PX4RCCalibration
::
rcCalFunctions
function
,
enum
PX4RCCalibrationTest
::
MoveToDirection
direction
,
bool
identifyStep
)
{
Q_UNUSED
(
functionStr
);
//qDebug(
) << "_stickMoveAutoStep function:direction:reversed:identifyStep" << functionStr << function << direction << identifyStep;
qCDebug
(
PX4RCCalibrationTestLog
)
<<
"_stickMoveAutoStep function:direction:reversed:identifyStep"
<<
functionStr
<<
function
<<
direction
<<
identifyStep
;
CHK_BUTTONS
(
cancelButtonMask
);
...
...
@@ -345,7 +329,6 @@ void PX4RCCalibrationTest::_switchMinMaxStep(void)
// Send min/max values switch channels
for
(
int
chan
=
0
;
chan
<
_availableChannels
;
chan
++
)
{
//qDebug() << chan << _rgChannelSettingsPreValidate[chan].rcMin << _rgChannelSettingsPreValidate[chan].rcMax;
_mockUAS
->
emitRemoteControlChannelRawChanged
(
chan
,
_rgChannelSettings
[
chan
].
rcMin
);
_mockUAS
->
emitRemoteControlChannelRawChanged
(
chan
,
_rgChannelSettings
[
chan
].
rcMax
);
}
...
...
@@ -361,7 +344,7 @@ void PX4RCCalibrationTest::_flapsDetectStep(void)
{
int
channel
=
_rgFunctionChannelMap
[
PX4RCCalibration
::
rcCalFunctionFlaps
];
//qDebug(
) << "_flapsDetectStep channel" << channel;
qCDebug
(
PX4RCCalibrationTestLog
)
<<
"_flapsDetectStep channel"
<<
channel
;
// Test code can't handle reversed flaps channel
Q_ASSERT
(
!
_rgChannelSettings
[
channel
].
reversed
);
...
...
@@ -387,7 +370,7 @@ void PX4RCCalibrationTest::_flapsDetectStep(void)
void
PX4RCCalibrationTest
::
_switchSelectAutoStep
(
const
char
*
functionStr
,
PX4RCCalibration
::
rcCalFunctions
function
)
{
Q_UNUSED
(
functionStr
);
//
qDebug
() << "_switchSelectAutoStep" << functionStr << "function:" << function;
//
//qCDebug(PX4RCCalibrationTestLog)
() << "_switchSelectAutoStep" << functionStr << "function:" << function;
int
buttonMask
=
cancelButtonMask
;
if
(
function
!=
PX4RCCalibration
::
rcCalFunctionModeSwitch
)
{
...
...
@@ -408,6 +391,50 @@ void PX4RCCalibrationTest::_switchSelectAutoStep(const char* functionStr, PX4RCC
void
PX4RCCalibrationTest
::
_fullCalibration_test
(
void
)
{
// IMPORTANT NOTE: We used channels 1-5 for attitude mapping in the test below.
// MockLink.param file cannot have flight mode switches mapped to those channels.
// If it does it will cause errors since the stick will not be detetected where
MockQGCUASParamManager
*
paramMgr
=
_mockUAS
->
getMockQGCUASParamManager
();
MockQGCUASParamManager
::
ParamMap_t
mapParamsSet
=
paramMgr
->
getMockSetParameters
();
/// _rgFunctionChannelMap maps from function index to channel index. For channels which are not part of
/// rc cal set the mapping the the previous mapping.
for
(
int
function
=
0
;
function
<
PX4RCCalibration
::
rcCalFunctionMax
;
function
++
)
{
bool
found
=
false
;
// If we are mapping this function during cal set it into _rgFunctionChannelMap
for
(
int
channel
=
0
;
channel
<
PX4RCCalibrationTest
::
_availableChannels
;
channel
++
)
{
if
(
_rgChannelSettings
[
channel
].
function
==
function
)
{
// First make sure this function isn't being use for a switch
QStringList
switchList
;
switchList
<<
"RC_MAP_MODE_SW"
<<
"RC_MAP_LOITER_SW"
<<
"RC_MAP_RETURN_SW"
<<
"RC_MAP_POSCTL_SW"
;
foreach
(
QString
switchParam
,
switchList
)
{
Q_ASSERT
(
mapParamsSet
[
switchParam
].
toInt
()
!=
channel
+
1
);
}
_rgFunctionChannelMap
[
function
]
=
channel
;
found
=
true
;
break
;
}
}
// If we aren't mapping this function during calibration, set it to the previous setting
if
(
!
found
)
{
_rgFunctionChannelMap
[
function
]
=
mapParamsSet
[
PX4RCCalibration
::
_rgFunctionInfo
[
function
].
parameterName
].
toInt
();
qCDebug
(
PX4RCCalibrationTestLog
)
<<
"Assigning switch"
<<
function
<<
mapParamsSet
[
PX4RCCalibration
::
_rgFunctionInfo
[
function
].
parameterName
].
toInt
();
if
(
_rgFunctionChannelMap
[
function
]
==
0
)
{
_rgFunctionChannelMap
[
function
]
=
-
1
;
// -1 signals no mapping
}
else
{
_rgFunctionChannelMap
[
function
]
--
;
// parameter is 1-based, _rgFunctionChannelMap is not
}
}
}
_channelHomePosition
();
QTest
::
mouseClick
(
_nextButton
,
Qt
::
LeftButton
);
...
...
@@ -466,6 +493,7 @@ void PX4RCCalibrationTest::_validateParameters(void)
expectedParameterValue
=
chanIndex
+
1
;
// 1-based parameter value
}
qCDebug
(
PX4RCCalibrationTestLog
)
<<
"Validate"
<<
chanFunction
<<
mapParamsSet
[
PX4RCCalibration
::
_rgFunctionInfo
[
chanFunction
].
parameterName
].
toInt
();
QCOMPARE
(
mapParamsSet
.
contains
(
PX4RCCalibration
::
_rgFunctionInfo
[
chanFunction
].
parameterName
),
true
);
QCOMPARE
(
mapParamsSet
[
PX4RCCalibration
::
_rgFunctionInfo
[
chanFunction
].
parameterName
].
toInt
(),
expectedParameterValue
);
}
...
...
@@ -496,8 +524,8 @@ void PX4RCCalibrationTest::_validateParameters(void)
QCOMPARE
(
convertOk
,
true
);
bool
rcReversedActual
=
(
rcReversedFloat
==
-
1.0
f
);
//qDebug(
) << "_validateParemeters expected channel:min:max:trim:rev" << chan << rcMinExpected << rcMaxExpected << rcTrimExpected << rcReversedExpected;
//qDebug(
) << "_validateParemeters actual channel:min:max:trim:rev" << chan << rcMinActual << rcMaxActual << rcTrimActual << rcReversedActual;
qCDebug
(
PX4RCCalibrationTestLog
)
<<
"_validateParemeters expected channel:min:max:trim:rev"
<<
chan
<<
rcMinExpected
<<
rcMaxExpected
<<
rcTrimExpected
<<
rcReversedExpected
;
qCDebug
(
PX4RCCalibrationTestLog
)
<<
"_validateParemeters actual channel:min:max:trim:rev"
<<
chan
<<
rcMinActual
<<
rcMaxActual
<<
rcTrimActual
<<
rcReversedActual
;
QCOMPARE
(
rcMinExpected
,
rcMinActual
);
QCOMPARE
(
rcMaxExpected
,
rcMaxActual
);
...
...
@@ -515,7 +543,7 @@ void PX4RCCalibrationTest::_validateParameters(void)
}
else
{
expectedValue
=
_rgFunctionChannelMap
[
chanFunction
]
+
1
;
// 1-based
}
// q
Debug(
) << chanFunction << expectedValue << mapParamsSet[PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName].toInt();
// q
CDebug(PX4RCCalibrationTestLog
) << chanFunction << expectedValue << mapParamsSet[PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName].toInt();
QCOMPARE
(
mapParamsSet
[
PX4RCCalibration
::
_rgFunctionInfo
[
chanFunction
].
parameterName
].
toInt
(),
expectedValue
);
}
}
src/qgcunittest/PX4RCCalibrationTest.h
View file @
a03e816a
...
...
@@ -29,12 +29,15 @@
#include "MockUAS.h"
#include "MultiSignalSpy.h"
#include "px4_configuration/PX4RCCalibration.h"
#include "QGCLoggingCategory.h"
/// @file
/// @brief PX4RCCalibration Widget unit test
///
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY
(
PX4RCCalibrationTestLog
)
/// @brief PX4RCCalibration Widget unit test
class
PX4RCCalibrationTest
:
public
UnitTest
{
...
...
@@ -44,7 +47,6 @@ public:
PX4RCCalibrationTest
(
void
);
private
slots
:
void
initTestCase
(
void
);
void
init
(
void
);
void
cleanup
(
void
);
...
...
@@ -125,7 +127,7 @@ private:
static
const
struct
ChannelSettings
_rgChannelSettings
[
_availableChannels
];
static
const
struct
ChannelSettings
_rgChannelSettingsValidate
[
PX4RCCalibration
::
_chanMax
];
static
const
int
_rgFunctionChannelMap
[
PX4RCCalibration
::
rcCalFunctionMax
];
int
_rgFunctionChannelMap
[
PX4RCCalibration
::
rcCalFunctionMax
];
};
#endif
src/ui/px4_configuration/PX4RCCalibration.cc
View file @
a03e816a
...
...
@@ -31,6 +31,8 @@
#include "UASManager.h"
#include "QGCMessageBox.h"
QGC_LOGGING_CATEGORY
(
PX4RCCalibrationLog
,
"PX4RCCalibrationLog"
)
const
int
PX4RCCalibration
::
_updateInterval
=
150
;
///< Interval for timer which updates radio channel widgets
const
int
PX4RCCalibration
::
_rcCalPWMCenterPoint
=
((
PX4RCCalibration
::
_rcCalPWMValidMaxValue
-
PX4RCCalibration
::
_rcCalPWMValidMinValue
)
/
2.0
f
)
+
PX4RCCalibration
::
_rcCalPWMValidMinValue
;
// FIXME: Double check these mins againt 150% throws
...
...
@@ -262,7 +264,7 @@ void PX4RCCalibration::_remoteControlChannelRawChanged(int chan, float fval)
// We always update raw values
_rcRawValue
[
chan
]
=
fval
;
//qDebug(
) << "Raw value" << chan << fval;
qCDebug
(
PX4RCCalibrationLog
)
<<
"Raw value"
<<
chan
<<
fval
;
if
(
_currentStep
==
-
1
)
{
// Track the receiver channel count by keeping track of how many channels we see
...
...
@@ -330,7 +332,7 @@ void PX4RCCalibration::_saveAllTrims(void)
// trims reset to correct values.
for
(
int
i
=
0
;
i
<
_chanCount
;
i
++
)
{
//qDebug(
) << "_saveAllTrims trim" << _rcRawValue[i];
qCDebug
(
PX4RCCalibrationLog
)
<<
"_saveAllTrims trim"
<<
_rcRawValue
[
i
];
_rgChannelInfo
[
i
].
rcTrim
=
_rcRawValue
[
i
];
}
_nextStep
();
...
...
@@ -355,7 +357,7 @@ bool PX4RCCalibration::_stickSettleComplete(int value)
if
(
abs
(
_stickDetectValue
-
value
)
>
_rcCalSettleDelta
)
{
// Stick is moving too much to consider stopped
//qDebug(
) << "_stickSettleComplete still moving, _stickDetectValue:value" << _stickDetectValue << value;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_stickSettleComplete still moving, _stickDetectValue:value"
<<
_stickDetectValue
<<
value
;
_stickDetectValue
=
value
;
_stickDetectSettleStarted
=
false
;
...
...
@@ -372,7 +374,7 @@ bool PX4RCCalibration::_stickSettleComplete(int value)
}
else
{
// Start waiting for the stick to stay settled for _stickDetectSettleWaitMSecs msecs
//qDebug(
) << "_stickSettleComplete starting settle timer, _stickDetectValue:value" << _stickDetectValue << value;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_stickSettleComplete starting settle timer, _stickDetectValue:value"
<<
_stickDetectValue
<<
value
;
_stickDetectSettleStarted
=
true
;
_stickDetectSettleElapsed
.
start
();
...
...
@@ -384,7 +386,7 @@ bool PX4RCCalibration::_stickSettleComplete(int value)
void
PX4RCCalibration
::
_inputStickDetect
(
enum
rcCalFunctions
function
,
int
channel
,
int
value
)
{
//qDebug() << "_inputStickDetect function:channel:value" << function
<< channel << value;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_inputStickDetect function:channel:value"
<<
_rgFunctionInfo
[
function
].
parameterName
<<
channel
<<
value
;
// If this channel is already used in a mapping we can't use it again
if
(
_rgChannelInfo
[
channel
].
function
!=
rcCalFunctionMax
)
{
...
...
@@ -397,7 +399,7 @@ void PX4RCCalibration::_inputStickDetect(enum rcCalFunctions function, int chann
if
(
abs
(
_rcValueSave
[
channel
]
-
value
)
>
_rcCalMoveDelta
)
{
// Stick has moved far enough to consider it as being selected for the function
//qDebug(
) << "_inputStickDetect starting settle wait, function:channel:value" << function << channel << value;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_inputStickDetect starting settle wait, function:channel:value"
<<
function
<<
channel
<<
value
;
// Setup up to detect stick being pegged to min or max value
_stickDetectChannel
=
channel
;
...
...
@@ -408,7 +410,7 @@ void PX4RCCalibration::_inputStickDetect(enum rcCalFunctions function, int chann
if
(
_stickSettleComplete
(
value
))
{
ChannelInfo
*
info
=
&
_rgChannelInfo
[
channel
];
//qDebug(
) << "_inputStickDetect settle complete, function:channel:value" << function << channel << value;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_inputStickDetect settle complete, function:channel:value"
<<
function
<<
channel
<<
value
;
// Stick detection is complete. Stick should be at max position.
// Map the channel to the function
...
...
@@ -515,7 +517,7 @@ void PX4RCCalibration::_inputSwitchMinMax(enum rcCalFunctions function, int chan
if
(
value
<
_rcCalPWMCenterPoint
)
{
int
minValue
=
qMin
(
_rgChannelInfo
[
channel
].
rcMin
,
value
);
//qDebug(
) << "_inputSwitchMinMax setting min channel:min" << channel << minValue;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_inputSwitchMinMax setting min channel:min"
<<
channel
<<
minValue
;
_rgChannelInfo
[
channel
].
rcMin
=
minValue
;
_rgRCValueMonitorWidget
[
channel
]
->
setMin
(
minValue
);
...
...
@@ -523,7 +525,7 @@ void PX4RCCalibration::_inputSwitchMinMax(enum rcCalFunctions function, int chan
}
else
{
int
maxValue
=
qMax
(
_rgChannelInfo
[
channel
].
rcMax
,
value
);
//qDebug(
) << "_inputSwitchMinMax setting max channel:max" << channel << maxValue;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_inputSwitchMinMax setting max channel:max"
<<
channel
<<
maxValue
;
_rgChannelInfo
[
channel
].
rcMax
=
maxValue
;
_rgRCValueMonitorWidget
[
channel
]
->
setMax
(
maxValue
);
...
...
@@ -651,7 +653,7 @@ void PX4RCCalibration::_switchDetect(enum rcCalFunctions function, int channel,
_rgFunctionChannelMapping
[
function
]
=
channel
;
info
->
function
=
function
;
//qDebug(
) << "Function:" << function << "mapped to:" << channel;
qCDebug
(
PX4RCCalibrationLog
)
<<
"Function:"
<<
function
<<
"mapped to:"
<<
channel
;
if
(
moveToNextStep
)
{
_nextStep
();
...
...
@@ -682,7 +684,7 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void)
info
->
rcTrim
=
PX4RCCalibration
::
_rcCalPWMCenterPoint
;
}
// Initialize function mapping to function channel not set
// Initialize
attitude
function mapping to function channel not set
for
(
size_t
i
=
0
;
i
<
rcCalFunctionMax
;
i
++
)
{
_rgFunctionChannelMapping
[
i
]
=
_chanMax
;
}
...
...
@@ -709,16 +711,17 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void)
Q_UNUSED
(
paramFound
);
bool
ok
;
int
c
hannel
=
value
.
toInt
(
&
ok
);
int
switchC
hannel
=
value
.
toInt
(
&
ok
);
Q_ASSERT
(
ok
);
Q_UNUSED
(
ok
);
// Parameter: 1-based channel, 0=not mapped
// _rgFunctionChannelMapping: 0-based channel, _chanMax=not mapped
_rgFunctionChannelMapping
[
curFunction
]
=
(
channel
==
0
)
?
_chanMax
:
channel
;
if
(
channel
!=
0
)
{
_rgChannelInfo
[
channel
-
1
].
function
=
curFunction
;
if
(
switchChannel
!=
0
)
{
qCDebug
(
PX4RCCalibrationLog
)
<<
"Reserving 0-based switch channel"
<<
switchChannel
-
1
;
_rgFunctionChannelMapping
[
curFunction
]
=
switchChannel
-
1
;
_rgChannelInfo
[
switchChannel
-
1
].
function
=
curFunction
;
}
}
}
...
...
@@ -848,7 +851,7 @@ void PX4RCCalibration::_validateCalibration(void)
// Validate Min/Max values. Although the channel appears as available we still may
// not have good min/max/trim values for it. Set to defaults if needed.
if
(
info
->
rcMin
>
_rcCalPWMValidMinValue
||
info
->
rcMax
<
_rcCalPWMValidMaxValue
)
{
//qDebug(
) << "_validateCalibration resetting channel" << chan;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_validateCalibration resetting channel"
<<
chan
;
info
->
rcMin
=
_rcCalPWMDefaultMinValue
;
info
->
rcMax
=
_rcCalPWMDefaultMaxValue
;
info
->
rcTrim
=
info
->
rcMin
+
((
info
->
rcMax
-
info
->
rcMin
)
/
2
);
...
...
@@ -874,7 +877,7 @@ void PX4RCCalibration::_validateCalibration(void)
}
}
else
{
// Unavailable channels are set to defaults
//qDebug(
) << "_validateCalibration resetting unavailable channel" << chan;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_validateCalibration resetting unavailable channel"
<<
chan
;
info
->
rcMin
=
_rcCalPWMDefaultMinValue
;
info
->
rcMax
=
_rcCalPWMDefaultMaxValue
;
info
->
rcTrim
=
info
->
rcMin
+
((
info
->
rcMax
-
info
->
rcMin
)
/
2
);
...
...
@@ -943,7 +946,7 @@ void PX4RCCalibration::_updateView()
valueWidget
->
setVisible
(
true
);
_rgRCValueMonitorLabel
[
chan
]
->
setVisible
(
true
);
//q
Debug(
) << "Visible" << valueWidget->objectName() << chan;
//q
CDebug(PX4RCCalibrationLog
) << "Visible" << valueWidget->objectName() << chan;
struct
ChannelInfo
*
info
=
&
_rgChannelInfo
[
chan
];
valueWidget
->
setValueAndMinMax
(
_rcRawValue
[
chan
],
info
->
rcMin
,
info
->
rcMax
);
...
...
@@ -970,7 +973,7 @@ void PX4RCCalibration::_updateView()
for
(
int
chan
=
_chanCount
;
chan
<
_chanMax
;
chan
++
)
{
_rgRCValueMonitorWidget
[
chan
]
->
setVisible
(
false
);
_rgRCValueMonitorLabel
[
chan
]
->
setVisible
(
false
);
//qDebug() << "Off
" << _rgRCValueMonitorWidget[chan]->objectName() << chan;
qCDebug
(
PX4RCCalibrationLog
)
<<
"Hiding channel
"
<<
_rgRCValueMonitorWidget
[
chan
]
->
objectName
()
<<
chan
;
}
}
...
...
@@ -1016,7 +1019,7 @@ void PX4RCCalibration::_stopCalibration(void)
/// @brief Saves the current channel values, so that we can detect when the use moves an input.
void
PX4RCCalibration
::
_rcCalSaveCurrentValues
(
void
)
{
//qDebug(
) << "_rcCalSaveCurrentValues";
qCDebug
(
PX4RCCalibrationLog
)
<<
"_rcCalSaveCurrentValues"
;
for
(
unsigned
i
=
0
;
i
<
_chanMax
;
i
++
)
{
_rcValueSave
[
i
]
=
_rcRawValue
[
i
];
}
...
...
@@ -1136,7 +1139,7 @@ void PX4RCCalibration::_setHelpImage(const char* imageFile)
}
file
+=
imageFile
;
//qDebug(
) << "_setHelpImage" << file;
qCDebug
(
PX4RCCalibrationLog
)
<<
"_setHelpImage"
<<
file
;
_ui
->
radioIcon
->
setPixmap
(
QPixmap
(
file
));
}
src/ui/px4_configuration/PX4RCCalibration.h
View file @
a03e816a
...
...
@@ -34,9 +34,12 @@
#include "UASInterface.h"
#include "RCValueWidget.h"
#include "QGCLoggingCategory.h"
#include "ui_PX4RCCalibration.h"
Q_DECLARE_LOGGING_CATEGORY
(
PX4RCCalibrationLog
)
class
PX4RCCalibrationTest
;
namespace
Ui
{
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment