Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
c7488064
Commit
c7488064
authored
Aug 20, 2014
by
Don Gagne
Browse files
New implementation of PX4 RC Calibration
parent
04293e2c
Changes
3
Expand all
Hide whitespace changes
Inline
Side-by-side
src/ui/px4_configuration/PX4RCCalibration.cc
0 → 100644
View file @
c7488064
This diff is collapsed.
Click to expand it.
src/ui/px4_configuration/PX4RCCalibration.h
0 → 100644
View file @
c7488064
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @brief PX4 RC Calibration Widget
/// @author Don Gagne <don@thegagnes.com
#ifndef PX4RCCalibration_H
#define PX4RCCalibration_H
#include
<QWidget>
#include
<QTimer>
#include
"QGCToolWidget.h"
#include
"UASInterface.h"
#include
"ui_PX4RCCalibration.h"
class
PX4RCCalibrationTest
;
namespace
Ui
{
class
PX4RCCalibration
;
}
class
PX4RCCalibration
:
public
QWidget
{
Q_OBJECT
friend
class
PX4RCCalibrationTest
;
///< This allows our unit test to access internal information needed.
public:
explicit
PX4RCCalibration
(
QWidget
*
parent
=
0
);
private
slots
:
void
_rcCalNext
(
void
);
void
_rcCalTryAgain
(
void
);
void
_rcCalSkip
(
void
);
void
_rcCalCancel
(
void
);
void
_updateView
(
void
);
void
_remoteControlChannelRawChanged
(
int
chan
,
float
val
);
void
_setActiveUAS
(
UASInterface
*
uas
);
void
_toggleSpektrumPairing
(
bool
enabled
);
private:
/// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo
/// aray.
enum
rcCalFunctions
{
rcCalFunctionRoll
,
rcCalFunctionPitch
,
rcCalFunctionYaw
,
rcCalFunctionThrottle
,
rcCalFunctionModeSwitch
,
rcCalFunctionPosCtlSwitch
,
rcCalFunctionLoiterSwitch
,
rcCalFunctionReturnSwitch
,
rcCalFunctionFlaps
,
rcCalFunctionAux1
,
rcCalFunctionAux2
,
rcCalFunctionMax
,
// Attitude functions are roll/pitch/yaw/throttle
rcCalFunctionFirstAttitudeFunction
=
rcCalFunctionRoll
,
rcCalFunctionLastAttitudeFunction
=
rcCalFunctionThrottle
,
// Non-Attitude functions are everthing else
rcCalFunctionFirstNonAttitudeFunction
=
rcCalFunctionModeSwitch
,
rcCalFunctionLastNonAttitudeFunction
=
rcCalFunctionAux2
,
};
/// @brief The states of the calibration state machine.
enum
rcCalStates
{
rcCalStateChannelWait
,
rcCalStateBegin
,
rcCalStateIdentify
,
rcCalStateMinMax
,
rcCalStateCenterThrottle
,
rcCalStateDetectInversion
,
rcCalStateTrims
,
rcCalStateSave
};
/// @brief A set of information associated with a function.
struct
FunctionInfo
{
const
char
*
functionName
;
///< User visible function name
const
char
*
inversionMsg
;
///< Message to display to user to detect inversion
const
char
*
parameterName
;
///< Parameter name for function mapping
bool
required
;
///< true: function must be mapped
};
/// @brief A set of information associated with a radio channel.
struct
ChannelInfo
{
enum
rcCalFunctions
function
;
///< Function mapped to this channel, rcCalFunctionMax for none
bool
reversed
;
///< true: channel is reverse, false: not reversed
float
rcMin
;
///< Minimum RC value
float
rcMax
;
///< Maximum RC value
float
rcTrim
;
///< Trim position
};
// Methods - see source code for documentation
void
_writeCalibration
(
bool
trimsOnly
);
void
_resetInternalCalibrationValues
(
void
);
void
_copyAndSetTrims
(
void
);
void
_rcCalChannelWait
(
bool
firstTime
);
void
_rcCalBegin
(
void
);
void
_rcCalNextIdentifyChannelMapping
(
void
);
void
_rcCalReadChannelsMinMax
(
void
);
void
_rcCalCenterThrottle
(
void
);
void
_rcCalNextDetectChannelInversion
(
void
);
void
_rcCalTrims
(
void
);
void
_rcCalSave
(
void
);
void
_rcCalSaveCurrentValues
(
void
);
void
_showMinMaxOnRadioWidgets
(
bool
show
);
void
_unitTestForceCalState
(
enum
rcCalStates
state
);
// Member variables
static
const
int
_updateInterval
;
///< Interval for ui update timer
static
const
struct
FunctionInfo
_rgFunctionInfo
[
rcCalFunctionMax
];
///< Information associated with each function.
int
_rgFunctionChannelMapping
[
rcCalFunctionMax
];
///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function.
int
_chanCount
;
///< Number of actual rc channels available
static
const
int
_chanMax
=
18
;
///< Maximum number of supported rc channels
static
const
int
_chanMinimum
=
5
;
///< Minimum numner of channels required to run PX4
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
bool
_rcCalStateChannelComplete
;
///< Work associated with current channel is complete
int
_rcCalStateIdentifyOldMapping
;
///< Previous mapping for channel being currently identified
int
_rcCalStateReverseOldMapping
;
///< Previous mapping for channel being currently used to detect inversion
static
const
int
_rcCalPWMCenterPoint
;
///< PWM center value;
static
const
int
_rcCalPWMValidMinValue
;
///< Valid minimum PWM value
static
const
int
_rcCalPWMValidMaxValue
;
///< Valid maximum PWM value
static
const
int
_rcCalRoughCenterDelta
;
///< Delta around center point which is considered to be roughly centered
static
const
float
_rcCalMoveDelta
;
///< Amount of delta which is considered stick movement
static
const
float
_rcCalMinDelta
;
///< Amount of delta allowed around min value to consider channel at min
float
_rcValueSave
[
_chanMax
];
///< Saved values prior to detecting channel movement
float
_rcRawValue
[
_chanMax
];
///< Current set of raw channel values
QGCRadioChannelDisplay
*
_rgAttitudeRadioWidget
[
4
];
///< Array of Attitide Function radio channel widgets
QGCRadioChannelDisplay
*
_rgRadioWidget
[
_chanMax
];
///< Array of radio channel widgets
UASInterface
*
_mav
;
///< The current MAV
Ui
::
PX4RCCalibration
*
_ui
;
QTimer
_updateTimer
;
///< Timer used to update widgete ui
};
#endif // PX4RCCalibration_H
src/ui/px4_configuration/PX4RCCalibration.ui
0 → 100644
View file @
c7488064
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
PX4RCCalibration
</class>
<widget
class=
"QWidget"
name=
"PX4RCCalibration"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
1151
</width>
<height>
926
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout_2"
>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
rowstretch=
"0,0"
columnstretch=
"0,0,0"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"throttleWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
</widget>
</item>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"yawWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"pitchWidget"
native=
"true"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Preferred"
vsizetype=
"Preferred"
>
<horstretch>
1
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
</widget>
</item>
<item
row=
"1"
column=
"2"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"rollWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_9"
>
<item>
<widget
class=
"QPushButton"
name=
"rcCopyTrimButton"
>
<property
name=
"enabled"
>
<bool>
false
</bool>
</property>
<property
name=
"toolTip"
>
<string>
Copy the trim values from roll / pitch / yaw from manual flight to the autonomous flight modes.
</string>
</property>
<property
name=
"text"
>
<string>
Copy Attitude Trims
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"rcCalStatus"
>
<property
name=
"text"
>
<string>
TextLabel
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"rcCalFound"
>
<property
name=
"text"
>
<string>
TextLabel
</string>
</property>
</widget>
</item>
<item>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<item>
<widget
class=
"QPushButton"
name=
"rcCalTryAgain"
>
<property
name=
"text"
>
<string>
Try Again
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"rcCalSkip"
>
<property
name=
"text"
>
<string>
Skip
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"rcCalCancel"
>
<property
name=
"text"
>
<string>
Cancel
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"rcCalNext"
>
<property
name=
"text"
>
<string>
Next
</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer
name=
"verticalSpacer_3"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
20
</width>
<height>
40
</height>
</size>
</property>
</spacer>
</item>
<item>
<widget
class=
"QGroupBox"
name=
"groupBox"
>
<property
name=
"title"
>
<string>
Spektrum RC
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_10"
>
<item>
<widget
class=
"QPushButton"
name=
"spektrumPairButton"
>
<property
name=
"text"
>
<string>
Pair Receiver
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsm2RadioButton"
>
<property
name=
"text"
>
<string>
DSM2 Mode
</string>
</property>
<property
name=
"checked"
>
<bool>
true
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsmxRadioButton"
>
<property
name=
"text"
>
<string>
DSMX Mode (3 to 7 channels)
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsmx8RadioButton"
>
<property
name=
"text"
>
<string>
DSMX Mode (8 or more channels)
</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item
row=
"0"
column=
"1"
rowspan=
"2"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_6"
>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio1Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio2Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio3Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio4Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio5Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio6Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio7Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio8Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio9Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio10Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio11Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio12Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio13Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio14Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio15Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio16Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio17Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio18Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<spacer
name=
"verticalSpacer_4"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
20
</width>
<height>
40
</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item
row=
"1"
column=
"0"
>
<spacer
name=
"verticalSpacer"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
20
</width>
<height>
40
</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>
QGCRadioChannelDisplay
</class>
<extends>
QWidget
</extends>
<header>
ui/designer/QGCRadioChannelDisplay.h
</header>
<container>
1
</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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