Commit b8e67980 authored by Don Gagne's avatar Don Gagne

APM Radio Config

Refactored PX4 radio config to work with both PX4 and APM
parent 8ffe06fe
...@@ -499,7 +499,7 @@ HEADERS += \ ...@@ -499,7 +499,7 @@ HEADERS += \
src/qgcunittest/MavlinkLogTest.h \ src/qgcunittest/MavlinkLogTest.h \
src/qgcunittest/MessageBoxTest.h \ src/qgcunittest/MessageBoxTest.h \
src/qgcunittest/MultiSignalSpy.h \ src/qgcunittest/MultiSignalSpy.h \
src/qgcunittest/PX4RCCalibrationTest.h \ src/qgcunittest/RadioConfigTest.h \
src/qgcunittest/TCPLinkTest.h \ src/qgcunittest/TCPLinkTest.h \
src/qgcunittest/TCPLoopBackServer.h \ src/qgcunittest/TCPLoopBackServer.h \
src/qgcunittest/UnitTest.h \ src/qgcunittest/UnitTest.h \
...@@ -522,7 +522,7 @@ SOURCES += \ ...@@ -522,7 +522,7 @@ SOURCES += \
src/qgcunittest/MavlinkLogTest.cc \ src/qgcunittest/MavlinkLogTest.cc \
src/qgcunittest/MessageBoxTest.cc \ src/qgcunittest/MessageBoxTest.cc \
src/qgcunittest/MultiSignalSpy.cc \ src/qgcunittest/MultiSignalSpy.cc \
src/qgcunittest/PX4RCCalibrationTest.cc \ src/qgcunittest/RadioConfigTest.cc \
src/qgcunittest/TCPLinkTest.cc \ src/qgcunittest/TCPLinkTest.cc \
src/qgcunittest/TCPLoopBackServer.cc \ src/qgcunittest/TCPLoopBackServer.cc \
src/qgcunittest/UnitTest.cc \ src/qgcunittest/UnitTest.cc \
...@@ -536,6 +536,7 @@ SOURCES += \ ...@@ -536,6 +536,7 @@ SOURCES += \
# #
INCLUDEPATH += \ INCLUDEPATH += \
src/AutoPilotPlugins/Common \
src/AutoPilotPlugins/PX4 \ src/AutoPilotPlugins/PX4 \
src/FirmwarePlugin \ src/FirmwarePlugin \
src/Vehicle \ src/Vehicle \
...@@ -547,6 +548,8 @@ HEADERS+= \ ...@@ -547,6 +548,8 @@ HEADERS+= \
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h \ src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h \
src/AutoPilotPlugins/APM/APMAirframeComponent.h \ src/AutoPilotPlugins/APM/APMAirframeComponent.h \
src/AutoPilotPlugins/APM/APMComponent.h \ src/AutoPilotPlugins/APM/APMComponent.h \
src/AutoPilotPlugins/APM/APMRadioComponent.h \
src/AutoPilotPlugins/Common/RadioComponentController.h \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \ src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \
src/AutoPilotPlugins/PX4/AirframeComponent.h \ src/AutoPilotPlugins/PX4/AirframeComponent.h \
src/AutoPilotPlugins/PX4/AirframeComponentAirframes.h \ src/AutoPilotPlugins/PX4/AirframeComponentAirframes.h \
...@@ -557,8 +560,7 @@ HEADERS+= \ ...@@ -557,8 +560,7 @@ HEADERS+= \
src/AutoPilotPlugins/PX4/PowerComponentController.h \ src/AutoPilotPlugins/PX4/PowerComponentController.h \
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h \ src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h \
src/AutoPilotPlugins/PX4/PX4Component.h \ src/AutoPilotPlugins/PX4/PX4Component.h \
src/AutoPilotPlugins/PX4/RadioComponent.h \ src/AutoPilotPlugins/PX4/PX4RadioComponent.h \
src/AutoPilotPlugins/PX4/RadioComponentController.h \
src/AutoPilotPlugins/PX4/SafetyComponent.h \ src/AutoPilotPlugins/PX4/SafetyComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponent.h \ src/AutoPilotPlugins/PX4/SensorsComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponentController.h \ src/AutoPilotPlugins/PX4/SensorsComponentController.h \
...@@ -591,6 +593,8 @@ SOURCES += \ ...@@ -591,6 +593,8 @@ SOURCES += \
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc \ src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc \
src/AutoPilotPlugins/APM/APMAirframeComponent.cc \ src/AutoPilotPlugins/APM/APMAirframeComponent.cc \
src/AutoPilotPlugins/APM/APMComponent.cc \ src/AutoPilotPlugins/APM/APMComponent.cc \
src/AutoPilotPlugins/APM/APMRadioComponent.cc \
src/AutoPilotPlugins/Common/RadioComponentController.cc \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \ src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \
src/AutoPilotPlugins/PX4/AirframeComponent.cc \ src/AutoPilotPlugins/PX4/AirframeComponent.cc \
src/AutoPilotPlugins/PX4/AirframeComponentAirframes.cc \ src/AutoPilotPlugins/PX4/AirframeComponentAirframes.cc \
...@@ -601,8 +605,7 @@ SOURCES += \ ...@@ -601,8 +605,7 @@ SOURCES += \
src/AutoPilotPlugins/PX4/PowerComponentController.cc \ src/AutoPilotPlugins/PX4/PowerComponentController.cc \
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc \ src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc \
src/AutoPilotPlugins/PX4/PX4Component.cc \ src/AutoPilotPlugins/PX4/PX4Component.cc \
src/AutoPilotPlugins/PX4/RadioComponent.cc \ src/AutoPilotPlugins/PX4/PX4RadioComponent.cc \
src/AutoPilotPlugins/PX4/RadioComponentController.cc \
src/AutoPilotPlugins/PX4/SafetyComponent.cc \ src/AutoPilotPlugins/PX4/SafetyComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponentController.cc \ src/AutoPilotPlugins/PX4/SensorsComponentController.cc \
......
...@@ -97,8 +97,9 @@ ...@@ -97,8 +97,9 @@
<file alias="QGroundControl/ScreenTools/qmldir">src/QmlControls/QGroundControl.ScreenTools.qmldir</file> <file alias="QGroundControl/ScreenTools/qmldir">src/QmlControls/QGroundControl.ScreenTools.qmldir</file>
<file alias="QGroundControl/ScreenTools/ScreenTools.qml">src/QmlControls/ScreenTools.qml</file> <file alias="QGroundControl/ScreenTools/ScreenTools.qml">src/QmlControls/ScreenTools.qml</file>
<file alias="QmlTest.qml">src/QmlControls/QmlTest.qml</file> <file alias="QmlTest.qml">src/QmlControls/QmlTest.qml</file>
<file alias="RadioComponent.qml">src/AutoPilotPlugins/PX4/RadioComponent.qml</file> <file alias="RadioComponent.qml">src/AutoPilotPlugins/Common/RadioComponent.qml</file>
<file alias="RadioComponentSummary.qml">src/AutoPilotPlugins/PX4/RadioComponentSummary.qml</file> <file alias="PX4RadioComponentSummary.qml">src/AutoPilotPlugins/PX4/PX4RadioComponentSummary.qml</file>
<file alias="APMRadioComponentSummary.qml">src/AutoPilotPlugins/APM/APMRadioComponentSummary.qml</file>
<file alias="SafetyComponent.qml">src/AutoPilotPlugins/PX4/SafetyComponent.qml</file> <file alias="SafetyComponent.qml">src/AutoPilotPlugins/PX4/SafetyComponent.qml</file>
<file alias="SafetyComponentSummary.qml">src/AutoPilotPlugins/PX4/SafetyComponentSummary.qml</file> <file alias="SafetyComponentSummary.qml">src/AutoPilotPlugins/PX4/SafetyComponentSummary.qml</file>
<file alias="SensorsComponent.qml">src/AutoPilotPlugins/PX4/SensorsComponent.qml</file> <file alias="SensorsComponent.qml">src/AutoPilotPlugins/PX4/SensorsComponent.qml</file>
......
...@@ -52,6 +52,11 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) ...@@ -52,6 +52,11 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
Q_CHECK_PTR(_airframeComponent); Q_CHECK_PTR(_airframeComponent);
_airframeComponent->setupTriggerSignals(); _airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
_radioComponent = new APMRadioComponent(_vehicle, this);
Q_CHECK_PTR(_radioComponent);
_radioComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
} else { } else {
qWarning() << "Call to vehicleCompenents prior to parametersReady"; qWarning() << "Call to vehicleCompenents prior to parametersReady";
} }
......
...@@ -27,6 +27,7 @@ ...@@ -27,6 +27,7 @@
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "Vehicle.h" #include "Vehicle.h"
#include "APMAirframeComponent.h" #include "APMAirframeComponent.h"
#include "APMRadioComponent.h"
/// This is the APM specific implementation of the AutoPilot class. /// This is the APM specific implementation of the AutoPilot class.
class APMAutoPilotPlugin : public AutoPilotPlugin class APMAutoPilotPlugin : public AutoPilotPlugin
...@@ -40,6 +41,9 @@ public: ...@@ -40,6 +41,9 @@ public:
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void); virtual const QVariantList& vehicleComponents(void);
APMAirframeComponent* airframeComponent(void) { return _airframeComponent; }
APMRadioComponent* radioComponent(void) { return _radioComponent; }
public slots: public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters); void _parametersReadyPreChecks(bool missingParameters);
...@@ -48,6 +52,7 @@ private: ...@@ -48,6 +52,7 @@ private:
bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed
QVariantList _components; QVariantList _components;
APMAirframeComponent* _airframeComponent; APMAirframeComponent* _airframeComponent;
APMRadioComponent* _radioComponent;
}; };
#endif #endif
/*=====================================================================
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/>.
======================================================================*/
#include "APMRadioComponent.h"
#include "APMAutoPilotPlugin.h"
APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
APMComponent(vehicle, autopilot, parent),
_name(tr("Radio"))
{
}
QString APMRadioComponent::name(void) const
{
return _name;
}
QString APMRadioComponent::description(void) const
{
return tr("The Radio Component is used to setup which channels on your RC Transmitter you will use for each vehicle control such as Roll, Pitch, Yaw and Throttle. "
"It also allows you to assign switches and dials to the various flight modes. "
"Prior to flight you must also calibrate the extents for all of your channels.");
}
QString APMRadioComponent::iconResource(void) const
{
return "/qmlimages/RadioComponentIcon.png";
}
bool APMRadioComponent::requiresSetup(void) const
{
return true;
}
bool APMRadioComponent::setupComplete(void) const
{
// The best we can do to detect the need for a radio calibration is look for attitude
// controls to be mapped.
QStringList attitudeMappings;
attitudeMappings << "RCMAP_ROLL" << "RCMAP_PITCH" << "RCMAP_YAW" << "RCMAP_THROTTLE";
foreach(QString mapParam, attitudeMappings) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) {
return false;
}
}
return true;
}
QString APMRadioComponent::setupStateDescription(void) const
{
const char* stateDescription;
if (requiresSetup()) {
stateDescription = "Requires calibration";
} else {
stateDescription = "Calibrated";
}
return QString(stateDescription);
}
QStringList APMRadioComponent::setupCompleteChangedTriggerList(void) const
{
QStringList triggers;
triggers << "RCMAP_ROLL" << "RCMAP_PITCH" << "RCMAP_YAW" << "RCMAP_THROTTLE";
return triggers;
}
QStringList APMRadioComponent::paramFilterList(void) const
{
QStringList list;
list << "RC*";
return list;
}
QUrl APMRadioComponent::setupSource(void) const
{
return QUrl::fromUserInput("qrc:/qml/RadioComponent.qml");
}
QUrl APMRadioComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput("qrc:/qml/APMRadioComponentSummary.qml");
}
QString APMRadioComponent::prerequisiteSetup(void) const
{
APMAutoPilotPlugin* plugin = dynamic_cast<APMAutoPilotPlugin*>(_autopilot);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
/*=====================================================================
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/>.
======================================================================*/
#ifndef APMRadioComponent_H
#define APMRadioComponent_H
#include "APMComponent.h"
class APMRadioComponent : public APMComponent
{
Q_OBJECT
public:
APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const;
// Virtuals from VehicleComponent
virtual QString name(void) const;
virtual QString description(void) const;
virtual QString iconResource(void) const;
virtual bool requiresSetup(void) const;
virtual bool setupComplete(void) const;
virtual QString setupStateDescription(void) const;
virtual QUrl setupSource(void) const;
virtual QStringList paramFilterList(void) const;
virtual QUrl summaryQmlSource(void) const;
virtual QString prerequisiteSetup(void) const;
private:
const QString _name;
QVariantList _summaryItems;
};
#endif
import QtQuick 2.2
import QtQuick.Controls 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
FactPanel {
id: panel
anchors.fill: parent
color: qgcPal.windowShadeDark
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
FactPanelController { id: controller; factPanel: panel }
property Fact mapRollFact: controller.getParameterFact(-1, "RCMAP_ROLL")
property Fact mapPitchFact: controller.getParameterFact(-1, "RCMAP_PITCH")
property Fact mapYawFact: controller.getParameterFact(-1, "RCMAP_YAW")
property Fact mapThrottleFact: controller.getParameterFact(-1, "RCMAP_THROTTLE")
Column {
anchors.fill: parent
anchors.margins: 8
VehicleSummaryRow {
labelText: "Roll:"
valueText: mapRollFact.value == 0 ? "Setup required" : mapRollFact.valueString
}
VehicleSummaryRow {
labelText: "Pitch:"
valueText: mapPitchFact.value == 0 ? "Setup required" : mapPitchFact.valueString
}
VehicleSummaryRow {
labelText: "Yaw:"
valueText: mapYawFact.value == 0 ? "Setup required" : mapYawFact.valueString
}
VehicleSummaryRow {
labelText: "Throttle:"
valueText: mapThrottleFact.value == 0 ? "Setup required" : mapThrottleFact.valueString
}
}
}
...@@ -21,20 +21,17 @@ ...@@ -21,20 +21,17 @@
======================================================================*/ ======================================================================*/
/// @file import QtQuick 2.5
/// @brief Radio Calibration
/// @author Don Gagne <don@thegagnes.com>
import QtQuick 2.2
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Dialogs 1.2 import QtQuick.Dialogs 1.2
import QGroundControl.FactSystem 1.0 import QGroundControl 1.0
import QGroundControl.FactControls 1.0 import QGroundControl.FactSystem 1.0
import QGroundControl.Palette 1.0 import QGroundControl.FactControls 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.Controls 1.0
import QGroundControl.Controllers 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
QGCView { QGCView {
id: rootQGCView id: rootQGCView
...@@ -42,19 +39,14 @@ QGCView { ...@@ -42,19 +39,14 @@ QGCView {
QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled }
readonly property string dialogTitle: "Radio" readonly property string dialogTitle: "Radio"
readonly property real labelToMonitorMargin: defaultTextWidth * 3 readonly property real labelToMonitorMargin: defaultTextWidth * 3
property bool controllerCompleted: false
property bool controllerAndViewReady: false
property Fact rcInMode: controller.getParameterFact(-1, "COM_RC_IN_MODE") property bool controllerCompleted: false
property bool controllerAndViewReady: false
function updateChannelCount() function updateChannelCount()
{ {
if (controllerAndViewReady) {
if (rcInMode.value == 1) {
showDialog(joystickEnabledDialogComponent, dialogTitle, 50, 0)
}
/* /*
FIXME: Turned off for now, since it prevents binding. Need to restructure to FIXME: Turned off for now, since it prevents binding. Need to restructure to
allow binding and still check channel count allow binding and still check channel count
...@@ -64,7 +56,6 @@ QGCView { ...@@ -64,7 +56,6 @@ QGCView {
hideDialog() hideDialog()
} }
*/ */
}
} }
RadioComponentController { RadioComponentController {
...@@ -75,8 +66,6 @@ QGCView { ...@@ -75,8 +66,6 @@ QGCView {
nextButton: nextButton nextButton: nextButton
skipButton: skipButton skipButton: skipButton
onChannelCountChanged: updateChannelCount()
Component.onCompleted: { Component.onCompleted: {
controllerCompleted = true controllerCompleted = true
if (rootQGCView.completedSignalled) { if (rootQGCView.completedSignalled) {
...@@ -85,6 +74,9 @@ QGCView { ...@@ -85,6 +74,9 @@ QGCView {
updateChannelCount() updateChannelCount()
} }
} }
onChannelCountChanged: updateChannelCount()
onFunctionMappingChangedAPMReboot: showMessage("Reboot required", "Your stick mappings have changed, you must reboot the vehicle for correct operation.", StandardButton.Ok)
} }
onCompleted: { onCompleted: {
...@@ -133,14 +125,6 @@ QGCView { ...@@ -133,14 +125,6 @@ QGCView {
} }
} }
Component {
id: joystickEnabledDialogComponent
QGCViewMessage {
message: "Radio Config is disabled since you have a Joystick enabled."
}
}
Component { Component {
id: spektrumBindDialogComponent id: spektrumBindDialogComponent
...@@ -482,6 +466,7 @@ QGCView { ...@@ -482,6 +466,7 @@ QGCView {
QGCButton { QGCButton {
showBorder: true showBorder: true
text: "Copy Trims" text: "Copy Trims"
visible: QGroundControl.multiVehicleManager.activeVehicle.px4Firmware
onClicked: showDialog(copyTrimsDialogComponent, dialogTitle, 50, StandardButton.Ok | StandardButton.Cancel) onClicked: showDialog(copyTrimsDialogComponent, dialogTitle, 50, StandardButton.Ok | StandardButton.Cancel)
} }
......
...@@ -140,9 +140,12 @@ signals: ...@@ -140,9 +140,12 @@ signals:
// @brief Signalled when in unit test mode and a message box should be displayed by the next button // @brief Signalled when in unit test mode and a message box should be displayed by the next button
void nextButtonMessageBoxDisplayed(void); void nextButtonMessageBoxDisplayed(void);
// Signaled to QML to indicator reboot is required
void functionMappingChangedAPMReboot(void);
private slots: private slots:
void _remoteControlChannelRawChanged(int chan, float val); void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
private: private:
/// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo /// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo
/// array. /// array.
...@@ -209,7 +212,9 @@ private: ...@@ -209,7 +212,9 @@ private:
int _currentStep; ///< Current step of state machine int _currentStep; ///< Current step of state machine
const struct stateMachineEntry* _getStateMachineEntry(int step); const struct stateMachineEntry* _getStateMachineEntry(int step) const;
const struct FunctionInfo* _functionInfo(void) const;
bool _px4Vehicle(void) const;
void _advanceState(void); void _advanceState(void);
void _setupCurrentState(void); void _setupCurrentState(void);
...@@ -251,6 +256,8 @@ private: ...@@ -251,6 +256,8 @@ private:
void _storeSettings(void); void _storeSettings(void);
void _signalAllAttiudeValueChanges(void); void _signalAllAttiudeValueChanges(void);
int _chanMax(void) const;
// @brief Called by unit test code to set the mode to unit testing // @brief Called by unit test code to set the mode to unit testing
void _setUnitTestMode(void){ _unitTestMode = true; } void _setUnitTestMode(void){ _unitTestMode = true; }
...@@ -279,16 +286,20 @@ private: ...@@ -279,16 +286,20 @@ private:
static const int _updateInterval; ///< Interval for ui update timer static const int _updateInterval; ///< Interval for ui update timer
static const struct FunctionInfo _rgFunctionInfo[rcCalFunctionMax]; ///< Information associated with each function. static const struct FunctionInfo _rgFunctionInfoAPM[rcCalFunctionMax]; ///< Information associated with each function, PX4 firmware
static const struct FunctionInfo _rgFunctionInfoPX4[rcCalFunctionMax]; ///< Information associated with each function, APM firmware
int _rgFunctionChannelMapping[rcCalFunctionMax]; ///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function. int _rgFunctionChannelMapping[rcCalFunctionMax]; ///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function.
static const int _attitudeControls = 5; static const int _attitudeControls = 5;
int _chanCount; ///< Number of actual rc channels available int _chanCount; ///< Number of actual rc channels available
static const int _chanMax = 18; ///< Maximum number of supported rc channels static const int _chanMaxPX4 = 18; ///< Maximum number of supported rc channels, PX4 Firmware
static const int _chanMinimum = 5; ///< Minimum numner of channels required to run PX4 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 _chanMinimum = 5; ///< Minimum numner of channels required to run
struct ChannelInfo _rgChannelInfo[_chanMax]; ///< Information associated with each rc channel struct ChannelInfo _rgChannelInfo[_chanMaxAny]; ///< Information associated with each rc channel
enum rcCalStates _rcCalState; ///< Current calibration state enum rcCalStates _rcCalState; ///< Current calibration state
int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion
...@@ -306,9 +317,9 @@ private: ...@@ -306,9 +317,9 @@ private:
static const int _rcCalSettleDelta; static const int _rcCalSettleDelta;
static const int _rcCalMinDelta; static const int _rcCalMinDelta;
int _rcValueSave[_chanMax]; ///< Saved values prior to detecting channel movement int _rcValueSave[_chanMaxAny]; ///< Saved values prior to detecting channel movement
int _rcRawValue[_chanMax]; ///< Current set of raw channel values int _rcRawValue[_chanMaxAny]; ///< Current set of raw channel values
int _stickDetectChannel; int _stickDetectChannel;
int _stickDetectInitialValue; int _stickDetectInitialValue;
......
...@@ -99,7 +99,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) ...@@ -99,7 +99,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
_airframeComponent->setupTriggerSignals(); _airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
_radioComponent = new RadioComponent(_vehicle, this); _radioComponent = new PX4RadioComponent(_vehicle, this);
Q_CHECK_PTR(_radioComponent); Q_CHECK_PTR(_radioComponent);
_radioComponent->setupTriggerSignals(); _radioComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
......
...@@ -27,7 +27,7 @@ ...@@ -27,7 +27,7 @@
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "PX4AirframeLoader.h" #include "PX4AirframeLoader.h"
#include "AirframeComponent.h" #include "AirframeComponent.h"
#include "RadioComponent.h" #include "PX4RadioComponent.h"
#include "FlightModesComponent.h" #include "FlightModesComponent.h"
#include "SensorsComponent.h" #include "SensorsComponent.h"
#include "SafetyComponent.h" #include "SafetyComponent.h"
...@@ -53,7 +53,7 @@ public: ...@@ -53,7 +53,7 @@ public:
// These methods should only be used by objects within the plugin // These methods should only be used by objects within the plugin
AirframeComponent* airframeComponent(void) { return _airframeComponent; } AirframeComponent* airframeComponent(void) { return _airframeComponent; }
RadioComponent* radioComponent(void) { return _radioComponent; } PX4RadioComponent* radioComponent(void) { return _radioComponent; }
FlightModesComponent* flightModesComponent(void) { return _flightModesComponent; } FlightModesComponent* flightModesComponent(void) { return _flightModesComponent; }
SensorsComponent* sensorsComponent(void) { return _sensorsComponent; } SensorsComponent* sensorsComponent(void) { return _sensorsComponent; }
SafetyComponent* safetyComponent(void) { return _safetyComponent; } SafetyComponent* safetyComponent(void) { return _safetyComponent; }
...@@ -67,7 +67,7 @@ private: ...@@ -67,7 +67,7 @@ private:
PX4AirframeLoader* _airframeFacts; PX4AirframeLoader* _airframeFacts;
QVariantList _components; QVariantList _components;
AirframeComponent* _airframeComponent; AirframeComponent* _airframeComponent;
RadioComponent* _radioComponent; PX4RadioComponent* _radioComponent;
FlightModesComponent* _flightModesComponent; FlightModesComponent* _flightModesComponent;
SensorsComponent* _sensorsComponent; SensorsComponent* _sensorsComponent;
SafetyComponent* _safetyComponent; SafetyComponent* _safetyComponent;
......
...@@ -21,42 +21,38 @@ ...@@ -21,42 +21,38 @@
======================================================================*/ ======================================================================*/
/// @file #include "PX4RadioComponent.h"
/// @author Don Gagne <don@thegagnes.com>
#include "RadioComponent.h"
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h" #include "PX4AutoPilotPlugin.h"
RadioComponent::RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : PX4RadioComponent::PX4RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(vehicle, autopilot, parent), PX4Component(vehicle, autopilot, parent),
_name(tr("Radio")) _name(tr("Radio"))
{ {
} }
QString RadioComponent::name(void) const QString PX4RadioComponent::name(void) const
{ {
return _name; return _name;
} }
QString RadioComponent::description(void) const QString PX4RadioComponent::description(void) const
{ {
return tr("The Radio Component is used to setup which channels on your RC Transmitter you will use for each vehicle control such as Roll, Pitch, Yaw and Throttle. " return tr("The Radio Component is used to setup which channels on your RC Transmitter you will use for each vehicle control such as Roll, Pitch, Yaw and Throttle. "
"It also allows you to assign switches and dials to the various flight modes. " "It also allows you to assign switches and dials to the various flight modes. "
"Prior to flight you must also calibrate the extents for all of your channels."); "Prior to flight you must also calibrate the extents for all of your channels.");
} }
QString RadioComponent::iconResource(void) const QString PX4RadioComponent::iconResource(void) const
{ {
return "/qmlimages/RadioComponentIcon.png"; return "/qmlimages/RadioComponentIcon.png";
} }
bool RadioComponent::requiresSetup(void) const bool PX4RadioComponent::requiresSetup(void) const
{ {
return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true; return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true;
} }
bool RadioComponent::setupComplete(void) const bool PX4RadioComponent::setupComplete(void) const
{ {
if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) { if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) {
// The best we can do to detect the need for a radio calibration is look for attitude // The best we can do to detect the need for a radio calibration is look for attitude
...@@ -73,7 +69,7 @@ bool RadioComponent::setupComplete(void) const ...@@ -73,7 +69,7 @@ bool RadioComponent::setupComplete(void) const
return true; return true;
} }
QString RadioComponent::setupStateDescription(void) const QString PX4RadioComponent::setupStateDescription(void) const
{ {
const char* stateDescription; const char* stateDescription;
...@@ -85,7 +81,7 @@ QString RadioComponent::setupStateDescription(void) const ...@@ -85,7 +81,7 @@ QString RadioComponent::setupStateDescription(void) const
return QString(stateDescription); return QString(stateDescription);
} }
QStringList RadioComponent::setupCompleteChangedTriggerList(void) const QStringList PX4RadioComponent::setupCompleteChangedTriggerList(void) const
{ {
QStringList triggers; QStringList triggers;
...@@ -94,7 +90,7 @@ QStringList RadioComponent::setupCompleteChangedTriggerList(void) const ...@@ -94,7 +90,7 @@ QStringList RadioComponent::setupCompleteChangedTriggerList(void) const
return triggers; return triggers;
} }
QStringList RadioComponent::paramFilterList(void) const QStringList PX4RadioComponent::paramFilterList(void) const
{ {
QStringList list; QStringList list;
...@@ -103,21 +99,20 @@ QStringList RadioComponent::paramFilterList(void) const ...@@ -103,21 +99,20 @@ QStringList RadioComponent::paramFilterList(void) const
return list; return list;
} }
QUrl RadioComponent::setupSource(void) const QUrl PX4RadioComponent::setupSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/RadioComponent.qml"); return QUrl::fromUserInput("qrc:/qml/RadioComponent.qml");
} }
QUrl RadioComponent::summaryQmlSource(void) const QUrl PX4RadioComponent::summaryQmlSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/RadioComponentSummary.qml"); return QUrl::fromUserInput("qrc:/qml/PX4RadioComponentSummary.qml");
} }
QString RadioComponent::prerequisiteSetup(void) const QString PX4RadioComponent::prerequisiteSetup(void) const
{ {
if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) { if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) {
PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot); PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) { if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name(); return plugin->airframeComponent()->name();
......
...@@ -21,22 +21,17 @@ ...@@ -21,22 +21,17 @@
======================================================================*/ ======================================================================*/
#ifndef RADIOCOMPONENT_H #ifndef PX4RadioComponent_H
#define RADIOCOMPONENT_H #define PX4RadioComponent_H
#include "PX4Component.h" #include "PX4Component.h"
/// @file class PX4RadioComponent : public PX4Component
/// @brief The Radio VehicleComponent is used to calibrate the trasmitter and assign function mapping
/// to channels.
/// @author Don Gagne <don@thegagnes.com>
class RadioComponent : public PX4Component
{ {
Q_OBJECT Q_OBJECT
public: public:
RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); PX4RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component // Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const; virtual QStringList setupCompleteChangedTriggerList(void) const;
......
...@@ -171,6 +171,11 @@ public: ...@@ -171,6 +171,11 @@ public:
// Called to signal app shutdown. Disconnects all links while turning off auto-connect. // Called to signal app shutdown. Disconnects all links while turning off auto-connect.
void shutdown(void); void shutdown(void);
#ifdef QT_DEBUG
// Only used by unit test tp restart after a shutdown
void restart(void) { setConnectionsAllowed(); }
#endif
/// @return true: specified link is an autoconnect link /// @return true: specified link is an autoconnect link
bool isAutoconnectLink(LinkInterface* link); bool isAutoconnectLink(LinkInterface* link);
......
...@@ -47,12 +47,11 @@ public: ...@@ -47,12 +47,11 @@ public:
RadioConfigTest(void); RadioConfigTest(void);
private slots: private slots:
void init(void);
void cleanup(void); void cleanup(void);
void _minRCChannels_test(void); void _fullCalibration_px4_test(void);
void _fullCalibration_test(void); void _fullCalibration_apm_test(void);
private: private:
/// @brief Modes to run worker functions /// @brief Modes to run worker functions
enum TestMode { enum TestMode {
...@@ -67,15 +66,6 @@ private: ...@@ -67,15 +66,6 @@ private:
moveToCenter, moveToCenter,
}; };
void _channelHomePosition(void);
void _minRCChannels(void);
void _beginCalibration(void);
void _stickMoveWaitForSettle(int channel, int value);
void _stickMoveAutoStep(const char* functionStr, enum RadioComponentController::rcCalFunctions function, enum MoveToDirection direction, bool identifyStep);
void _switchMinMaxStep(void);
void _flapsDetectStep(void);
void _switchSelectAutoStep(const char* functionStr, RadioComponentController::rcCalFunctions function);
enum { enum {
validateMinMaxMask = 1 << 0, validateMinMaxMask = 1 << 0,
validateTrimsMask = 1 << 1, validateTrimsMask = 1 << 1,
...@@ -85,12 +75,28 @@ private: ...@@ -85,12 +75,28 @@ private:
}; };
struct ChannelSettings { struct ChannelSettings {
int function; int function;
int rcMin; int rcMin;
int rcMax; int rcMax;
int rcTrim; int rcTrim;
int reversed; int reversed;
}; };
void _init(MAV_AUTOPILOT firmwareType);
void _channelHomePosition(void);
void _minRCChannels(void);
void _beginCalibration(void);
void _stickMoveWaitForSettle(int channel, int value);
void _stickMoveAutoStep(const char* functionStr, enum RadioComponentController::rcCalFunctions function, enum MoveToDirection direction, bool identifyStep);
void _switchMinMaxStep(void);
void _flapsDetectStep(void);
void _switchSelectAutoStep(const char* functionStr, RadioComponentController::rcCalFunctions function);
bool _px4Vehicle(void) const;
const struct RadioComponentController::FunctionInfo* _functionInfo(void) const;
const struct ChannelSettings* _channelSettings(void) const;
const struct ChannelSettings* _channelSettingsValidate(void) const;
void _fullCalibrationWorker(MAV_AUTOPILOT firmwareType);
int _chanMax(void) const;
void _validateParameters(void); void _validateParameters(void);
...@@ -113,12 +119,13 @@ private: ...@@ -113,12 +119,13 @@ private:
static const int _testMaxValue; static const int _testMaxValue;
static const int _testCenterValue; static const int _testCenterValue;
static const int _availableChannels = 18; ///< Simulate 18 channel RC Transmitter
static const int _stickSettleWait; static const int _stickSettleWait;
static const struct ChannelSettings _rgChannelSettings[_availableChannels]; static const struct ChannelSettings _rgChannelSettingsPX4[RadioComponentController::_chanMaxPX4];
static const struct ChannelSettings _rgChannelSettingsValidate[RadioComponentController::_chanMax]; static const struct ChannelSettings _rgChannelSettingsAPM[RadioComponentController::_chanMaxAPM];
static const struct ChannelSettings _rgChannelSettingsValidatePX4[RadioComponentController::_chanMaxPX4];
static const struct ChannelSettings _rgChannelSettingsValidateAPM[RadioComponentController::_chanMaxAPM];
int _rgFunctionChannelMap[RadioComponentController::rcCalFunctionMax]; int _rgFunctionChannelMap[RadioComponentController::rcCalFunctionMax];
RadioComponentController* _controller; RadioComponentController* _controller;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment