Commit 745fff0c authored by Don Gagne's avatar Don Gagne

Merge pull request #2358 from DonLakeFlyer/APMRadioConfig

APM Stack Radio Config
parents 1cc4c7d8 b5c86dd0
......@@ -514,7 +514,7 @@ HEADERS += \
src/qgcunittest/MavlinkLogTest.h \
src/qgcunittest/MessageBoxTest.h \
src/qgcunittest/MultiSignalSpy.h \
src/qgcunittest/PX4RCCalibrationTest.h \
src/qgcunittest/RadioConfigTest.h \
src/qgcunittest/TCPLinkTest.h \
src/qgcunittest/TCPLoopBackServer.h \
src/qgcunittest/UnitTest.h \
......@@ -537,7 +537,7 @@ SOURCES += \
src/qgcunittest/MavlinkLogTest.cc \
src/qgcunittest/MessageBoxTest.cc \
src/qgcunittest/MultiSignalSpy.cc \
src/qgcunittest/PX4RCCalibrationTest.cc \
src/qgcunittest/RadioConfigTest.cc \
src/qgcunittest/TCPLinkTest.cc \
src/qgcunittest/TCPLoopBackServer.cc \
src/qgcunittest/UnitTest.cc \
......@@ -551,6 +551,7 @@ SOURCES += \
#
INCLUDEPATH += \
src/AutoPilotPlugins/Common \
src/AutoPilotPlugins/PX4 \
src/FirmwarePlugin \
src/Vehicle \
......@@ -562,6 +563,8 @@ HEADERS+= \
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h \
src/AutoPilotPlugins/APM/APMAirframeComponent.h \
src/AutoPilotPlugins/APM/APMComponent.h \
src/AutoPilotPlugins/APM/APMRadioComponent.h \
src/AutoPilotPlugins/Common/RadioComponentController.h \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \
src/AutoPilotPlugins/PX4/AirframeComponent.h \
src/AutoPilotPlugins/PX4/AirframeComponentAirframes.h \
......@@ -572,8 +575,7 @@ HEADERS+= \
src/AutoPilotPlugins/PX4/PowerComponentController.h \
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h \
src/AutoPilotPlugins/PX4/PX4Component.h \
src/AutoPilotPlugins/PX4/RadioComponent.h \
src/AutoPilotPlugins/PX4/RadioComponentController.h \
src/AutoPilotPlugins/PX4/PX4RadioComponent.h \
src/AutoPilotPlugins/PX4/SafetyComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponentController.h \
......@@ -606,6 +608,8 @@ SOURCES += \
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc \
src/AutoPilotPlugins/APM/APMAirframeComponent.cc \
src/AutoPilotPlugins/APM/APMComponent.cc \
src/AutoPilotPlugins/APM/APMRadioComponent.cc \
src/AutoPilotPlugins/Common/RadioComponentController.cc \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \
src/AutoPilotPlugins/PX4/AirframeComponent.cc \
src/AutoPilotPlugins/PX4/AirframeComponentAirframes.cc \
......@@ -616,8 +620,7 @@ SOURCES += \
src/AutoPilotPlugins/PX4/PowerComponentController.cc \
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc \
src/AutoPilotPlugins/PX4/PX4Component.cc \
src/AutoPilotPlugins/PX4/RadioComponent.cc \
src/AutoPilotPlugins/PX4/RadioComponentController.cc \
src/AutoPilotPlugins/PX4/PX4RadioComponent.cc \
src/AutoPilotPlugins/PX4/SafetyComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponentController.cc \
......
......@@ -98,8 +98,9 @@
<file alias="QGroundControl/ScreenTools/qmldir">src/QmlControls/QGroundControl.ScreenTools.qmldir</file>
<file alias="QGroundControl/ScreenTools/ScreenTools.qml">src/QmlControls/ScreenTools.qml</file>
<file alias="QmlTest.qml">src/QmlControls/QmlTest.qml</file>
<file alias="RadioComponent.qml">src/AutoPilotPlugins/PX4/RadioComponent.qml</file>
<file alias="RadioComponentSummary.qml">src/AutoPilotPlugins/PX4/RadioComponentSummary.qml</file>
<file alias="RadioComponent.qml">src/AutoPilotPlugins/Common/RadioComponent.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="SafetyComponentSummary.qml">src/AutoPilotPlugins/PX4/SafetyComponentSummary.qml</file>
<file alias="SensorsComponent.qml">src/AutoPilotPlugins/PX4/SensorsComponent.qml</file>
......
......@@ -52,6 +52,11 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
Q_CHECK_PTR(_airframeComponent);
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
_radioComponent = new APMRadioComponent(_vehicle, this);
Q_CHECK_PTR(_radioComponent);
_radioComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
} else {
qWarning() << "Call to vehicleCompenents prior to parametersReady";
}
......
......@@ -27,6 +27,7 @@
#include "AutoPilotPlugin.h"
#include "Vehicle.h"
#include "APMAirframeComponent.h"
#include "APMRadioComponent.h"
/// This is the APM specific implementation of the AutoPilot class.
class APMAutoPilotPlugin : public AutoPilotPlugin
......@@ -40,6 +41,9 @@ public:
// Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void);
APMAirframeComponent* airframeComponent(void) { return _airframeComponent; }
APMRadioComponent* radioComponent(void) { return _radioComponent; }
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
......@@ -48,6 +52,7 @@ private:
bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed
QVariantList _components;
APMAirframeComponent* _airframeComponent;
APMRadioComponent* _radioComponent;
};
#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 @@
======================================================================*/
/// @file
/// @brief Radio Calibration
/// @author Don Gagne <don@thegagnes.com>
import QtQuick 2.2
import QtQuick 2.5
import QtQuick.Controls 1.2
import QtQuick.Dialogs 1.2
import QtQuick.Dialogs 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
import QGroundControl 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
QGCView {
id: rootQGCView
......@@ -42,19 +39,14 @@ QGCView {
QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled }
readonly property string dialogTitle: "Radio"
readonly property real labelToMonitorMargin: defaultTextWidth * 3
property bool controllerCompleted: false
property bool controllerAndViewReady: false
readonly property string dialogTitle: "Radio"
readonly property real labelToMonitorMargin: defaultTextWidth * 3
property Fact rcInMode: controller.getParameterFact(-1, "COM_RC_IN_MODE")
property bool controllerCompleted: false
property bool controllerAndViewReady: false
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
allow binding and still check channel count
......@@ -64,7 +56,6 @@ QGCView {
hideDialog()
}
*/
}
}
RadioComponentController {
......@@ -75,8 +66,6 @@ QGCView {
nextButton: nextButton
skipButton: skipButton
onChannelCountChanged: updateChannelCount()
Component.onCompleted: {
controllerCompleted = true
if (rootQGCView.completedSignalled) {
......@@ -85,6 +74,9 @@ QGCView {
updateChannelCount()
}
}
onChannelCountChanged: updateChannelCount()
onFunctionMappingChangedAPMReboot: showMessage("Reboot required", "Your stick mappings have changed, you must reboot the vehicle for correct operation.", StandardButton.Ok)
}
onCompleted: {
......@@ -133,14 +125,6 @@ QGCView {
}
}
Component {
id: joystickEnabledDialogComponent
QGCViewMessage {
message: "Radio Config is disabled since you have a Joystick enabled."
}
}
Component {
id: spektrumBindDialogComponent
......@@ -482,6 +466,7 @@ QGCView {
QGCButton {
showBorder: true
text: "Copy Trims"
visible: QGroundControl.multiVehicleManager.activeVehicle.px4Firmware
onClicked: showDialog(copyTrimsDialogComponent, dialogTitle, 50, StandardButton.Ok | StandardButton.Cancel)
}
......
......@@ -140,9 +140,12 @@ signals:
// @brief Signalled when in unit test mode and a message box should be displayed by the next button
void nextButtonMessageBoxDisplayed(void);
// Signaled to QML to indicator reboot is required
void functionMappingChangedAPMReboot(void);
private slots:
void _remoteControlChannelRawChanged(int chan, float val);
void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
private:
/// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo
/// array.
......@@ -209,7 +212,9 @@ private:
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 _setupCurrentState(void);
......@@ -251,6 +256,8 @@ private:
void _storeSettings(void);
void _signalAllAttiudeValueChanges(void);
int _chanMax(void) const;
// @brief Called by unit test code to set the mode to unit testing
void _setUnitTestMode(void){ _unitTestMode = true; }
......@@ -279,16 +286,20 @@ private:
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.
static const int _attitudeControls = 5;
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
static const int _chanMaxPX4 = 18; ///< Maximum number of supported rc channels, PX4 Firmware
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
int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion
......@@ -306,9 +317,9 @@ private:
static const int _rcCalSettleDelta;
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 _stickDetectInitialValue;
......
......@@ -55,12 +55,7 @@ FlightModesComponentController::FlightModesComponentController(void) :
_init();
_validateConfiguration();
connect(_uas, &UASInterface::remoteControlChannelRawChanged, this, &FlightModesComponentController::_remoteControlChannelRawChanged);
}
FlightModesComponentController::~FlightModesComponentController()
{
disconnect(_uas, &UASInterface::remoteControlChannelRawChanged, this, &FlightModesComponentController::_remoteControlChannelRawChanged);
connect(_vehicle, &Vehicle::rcChannelsChanged, this, &FlightModesComponentController::_rcChannelsChanged);
}
void FlightModesComponentController::_init(void)
......@@ -209,27 +204,29 @@ void FlightModesComponentController::_validateConfiguration(void)
}
}
/// @brief This routine is called whenever a raw value for an RC channel changes.
/// @param chan RC channel on which signal is coming from (0-based)
/// @param fval Current value for channel
void FlightModesComponentController::_remoteControlChannelRawChanged(int chan, float fval)
/// Connected to Vehicle::rcChannelsChanged signal
void FlightModesComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels])
{
Q_ASSERT(chan >= 0 && chan <= _chanMax);
if (fval < _rgRCMin[chan]) {
fval= _rgRCMin[chan];
}
if (fval > _rgRCMax[chan]) {
fval= _rgRCMax[chan];
}
float percentRange = (fval - _rgRCMin[chan]) / (float)(_rgRCMax[chan] - _rgRCMin[chan]);
if (_rgRCReversed[chan]) {
percentRange = 1.0 - percentRange;
for (int channel=0; channel<channelCount; channel++) {
int channelValue = pwmValues[channel];
if (channelValue != -1) {
if (channelValue < _rgRCMin[channel]) {
channelValue= _rgRCMin[channel];
}
if (channelValue > _rgRCMax[channel]) {
channelValue= _rgRCMax[channel];
}
float percentRange = (channelValue - _rgRCMin[channel]) / (float)(_rgRCMax[channel] - _rgRCMin[channel]);
if (_rgRCReversed[channel]) {
percentRange = 1.0 - percentRange;
}
_rcValues[channel] = percentRange;
}
}
_rcValues[chan] = percentRange;
_recalcModeSelections();
emit switchLiveRangeChanged();
......
......@@ -43,7 +43,6 @@ class FlightModesComponentController : public FactPanelController
public:
FlightModesComponentController(void);
~FlightModesComponentController();
Q_PROPERTY(bool validConfiguration MEMBER _validConfiguration CONSTANT)
Q_PROPERTY(QString configurationErrors MEMBER _configurationErrors CONSTANT)
......@@ -183,7 +182,7 @@ signals:
void modeRowsChanged(void);
private slots:
void _remoteControlChannelRawChanged(int chan, float fval);
void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
private:
double _switchLiveRange(const QString& param);
......
......@@ -99,7 +99,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
_radioComponent = new RadioComponent(_vehicle, this);
_radioComponent = new PX4RadioComponent(_vehicle, this);
Q_CHECK_PTR(_radioComponent);
_radioComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
......
......@@ -27,7 +27,7 @@
#include "AutoPilotPlugin.h"
#include "PX4AirframeLoader.h"
#include "AirframeComponent.h"
#include "RadioComponent.h"
#include "PX4RadioComponent.h"
#include "FlightModesComponent.h"
#include "SensorsComponent.h"
#include "SafetyComponent.h"
......@@ -53,7 +53,7 @@ public:
// These methods should only be used by objects within the plugin
AirframeComponent* airframeComponent(void) { return _airframeComponent; }
RadioComponent* radioComponent(void) { return _radioComponent; }
PX4RadioComponent* radioComponent(void) { return _radioComponent; }
FlightModesComponent* flightModesComponent(void) { return _flightModesComponent; }
SensorsComponent* sensorsComponent(void) { return _sensorsComponent; }
SafetyComponent* safetyComponent(void) { return _safetyComponent; }
......@@ -67,7 +67,7 @@ private:
PX4AirframeLoader* _airframeFacts;
QVariantList _components;
AirframeComponent* _airframeComponent;
RadioComponent* _radioComponent;
PX4RadioComponent* _radioComponent;
FlightModesComponent* _flightModesComponent;
SensorsComponent* _sensorsComponent;
SafetyComponent* _safetyComponent;
......
......@@ -21,42 +21,38 @@
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "RadioComponent.h"
#include "QGCQmlWidgetHolder.h"
#include "PX4RadioComponent.h"
#include "PX4AutoPilotPlugin.h"
RadioComponent::RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4RadioComponent::PX4RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(vehicle, autopilot, parent),
_name(tr("Radio"))
{
}
QString RadioComponent::name(void) const
QString PX4RadioComponent::name(void) const
{
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. "
"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 RadioComponent::iconResource(void) const
QString PX4RadioComponent::iconResource(void) const
{
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;
}
bool RadioComponent::setupComplete(void) const
bool PX4RadioComponent::setupComplete(void) const
{
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
......@@ -73,7 +69,7 @@ bool RadioComponent::setupComplete(void) const
return true;
}
QString RadioComponent::setupStateDescription(void) const
QString PX4RadioComponent::setupStateDescription(void) const
{
const char* stateDescription;
......@@ -85,7 +81,7 @@ QString RadioComponent::setupStateDescription(void) const
return QString(stateDescription);
}
QStringList RadioComponent::setupCompleteChangedTriggerList(void) const
QStringList PX4RadioComponent::setupCompleteChangedTriggerList(void) const
{
QStringList triggers;
......@@ -94,7 +90,7 @@ QStringList RadioComponent::setupCompleteChangedTriggerList(void) const
return triggers;
}
QStringList RadioComponent::paramFilterList(void) const
QStringList PX4RadioComponent::paramFilterList(void) const
{
QStringList list;
......@@ -103,21 +99,20 @@ QStringList RadioComponent::paramFilterList(void) const
return list;
}
QUrl RadioComponent::setupSource(void) const
QUrl PX4RadioComponent::setupSource(void) const
{
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) {
PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
......
......@@ -21,22 +21,17 @@
======================================================================*/
#ifndef RADIOCOMPONENT_H
#define RADIOCOMPONENT_H
#ifndef PX4RadioComponent_H
#define PX4RadioComponent_H
#include "PX4Component.h"
/// @file
/// @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
class PX4RadioComponent : public PX4Component
{
Q_OBJECT
public:
RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
PX4RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -119,9 +119,9 @@ FactPanel {
}
}
function __checkForEarlyDialog() {
function __checkForEarlyDialog(title) {
if (!completedSignalled) {
console.warn("showDialog|Message called before QGCView.completed signalled")
console.warn("showDialog|Message called before QGCView.completed signalled", title)
}
}
......@@ -131,7 +131,7 @@ FactPanel {
/// @param charWidth Width of dialog in characters (-1 for full parent width)
/// @param buttons Buttons to show in dialog using StandardButton enum
function showDialog(component, title, charWidth, buttons) {
if (__checkForEarlyDialog()) {
if (__checkForEarlyDialog(title)) {
return
}
......@@ -150,7 +150,7 @@ FactPanel {
}
function showMessage(title, message, buttons) {
if (__checkForEarlyDialog()) {
if (__checkForEarlyDialog(title)) {
return
}
......
......@@ -74,28 +74,10 @@ bool QGroundControlQmlGlobal::loadBoolGlobalSetting (const QString& key, bool de
return settings.value(key, defaultValue).toBool();
}
#ifdef QT_DEBUG
void QGroundControlQmlGlobal::_startMockLink(MockConfiguration* mockConfig)
{
LinkManager* linkManager = qgcApp()->toolbox()->linkManager();
mockConfig->setDynamic(true);
linkManager->linkConfigurations()->append(mockConfig);
linkManager->createConnectedLink(mockConfig);
}
#endif
void QGroundControlQmlGlobal::startPX4MockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockConfiguration* mockConfig = new MockConfiguration("PX4 MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_PX4);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
_startMockLink(mockConfig);
MockLink::startPX4MockLink(sendStatusText);
#else
Q_UNUSED(sendStatusText);
#endif
......@@ -104,13 +86,7 @@ void QGroundControlQmlGlobal::startPX4MockLink(bool sendStatusText)
void QGroundControlQmlGlobal::startGenericMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockConfiguration* mockConfig = new MockConfiguration("Generic MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
_startMockLink(mockConfig);
MockLink::startGenericMockLink(sendStatusText);
#else
Q_UNUSED(sendStatusText);
#endif
......@@ -119,13 +95,7 @@ void QGroundControlQmlGlobal::startGenericMockLink(bool sendStatusText)
void QGroundControlQmlGlobal::startAPMArduCopterMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
_startMockLink(mockConfig);
MockLink::startAPMArduCopterMockLink(sendStatusText);
#else
Q_UNUSED(sendStatusText);
#endif
......@@ -134,13 +104,7 @@ void QGroundControlQmlGlobal::startAPMArduCopterMockLink(bool sendStatusText)
void QGroundControlQmlGlobal::startAPMArduPlaneMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
mockConfig->setSendStatusText(sendStatusText);
_startMockLink(mockConfig);
MockLink::startAPMArduPlaneMockLink(sendStatusText);
#else
Q_UNUSED(sendStatusText);
#endif
......
......@@ -132,9 +132,6 @@ signals:
void virtualTabletJoystickChanged (bool enabled);
private:
#ifdef QT_DEBUG
void _startMockLink(MockConfiguration* mockConfig);
#endif
FlightMapSettings* _flightMapSettings;
HomePositionManager* _homePositionManager;
......
......@@ -119,10 +119,10 @@ Vehicle::Vehicle(LinkInterface* link,
setLatitude(_uas->getLatitude());
setLongitude(_uas->getLongitude());
connect(_uas, &UAS::latitudeChanged, this, &Vehicle::setLatitude);
connect(_uas, &UAS::longitudeChanged, this, &Vehicle::setLongitude);
connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady);
connect(_uas, &UAS::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged);
connect(_uas, &UAS::latitudeChanged, this, &Vehicle::setLatitude);
connect(_uas, &UAS::longitudeChanged, this, &Vehicle::setLongitude);
connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady);
connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged);
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
_autopilotPlugin = _autopilotPluginManager->newAutopilotPluginForVehicle(this);
......@@ -211,12 +211,18 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
_firmwarePlugin->adjustMavlinkMessage(&message);
switch (message.msgid) {
case MAVLINK_MSG_ID_HOME_POSITION:
_handleHomePosition(message);
break;
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartbeat(message);
break;
case MAVLINK_MSG_ID_HOME_POSITION:
_handleHomePosition(message);
break;
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartbeat(message);
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
_handleRCChannels(message);
break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
_handleRCChannelsRaw(message);
break;
}
emit mavlinkMessageReceived(message);
......@@ -282,6 +288,89 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message)
}
}
void Vehicle::_handleRCChannels(mavlink_message_t& message)
{
mavlink_rc_channels_t channels;
mavlink_msg_rc_channels_decode(&message, &channels);
uint16_t* _rgChannelvalues[cMaxRcChannels] = {
&channels.chan1_raw,
&channels.chan2_raw,
&channels.chan3_raw,
&channels.chan4_raw,
&channels.chan5_raw,
&channels.chan6_raw,
&channels.chan7_raw,
&channels.chan8_raw,
&channels.chan9_raw,
&channels.chan10_raw,
&channels.chan11_raw,
&channels.chan12_raw,
&channels.chan13_raw,
&channels.chan14_raw,
&channels.chan15_raw,
&channels.chan16_raw,
&channels.chan17_raw,
&channels.chan18_raw,
};
int pwmValues[cMaxRcChannels];
for (int i=0; i<cMaxRcChannels; i++) {
uint16_t channelValue = *_rgChannelvalues[i];
if (i < channels.chancount) {
pwmValues[i] = channelValue == UINT16_MAX ? -1 : channelValue;
} else {
pwmValues[i] = -1;
}
}
emit remoteControlRSSIChanged(channels.rssi);
emit rcChannelsChanged(channels.chancount, pwmValues);
}
void Vehicle::_handleRCChannelsRaw(mavlink_message_t& message)
{
// We handle both RC_CHANNLES and RC_CHANNELS_RAW since different firmware will only
// send one or the other.
mavlink_rc_channels_raw_t channels;
mavlink_msg_rc_channels_raw_decode(&message, &channels);
uint16_t* _rgChannelvalues[cMaxRcChannels] = {
&channels.chan1_raw,
&channels.chan2_raw,
&channels.chan3_raw,
&channels.chan4_raw,
&channels.chan5_raw,
&channels.chan6_raw,
&channels.chan7_raw,
&channels.chan8_raw,
};
int pwmValues[cMaxRcChannels];
int channelCount = 0;
for (int i=0; i<8; i++) {
uint16_t channelValue = *_rgChannelvalues[i];
if (channelValue == UINT16_MAX) {
pwmValues[i] = -1;
} else {
channelCount = i;
pwmValues[i] = channelValue;
}
}
for (int i=9; i<18; i++) {
pwmValues[i] = -1;
}
emit remoteControlRSSIChanged(channels.rssi);
emit rcChannelsChanged(channelCount, pwmValues);
}
bool Vehicle::_containsLink(LinkInterface* link)
{
return _links.contains(link);
......
......@@ -112,6 +112,9 @@ public:
Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged)
Q_PROPERTY(int flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged)
Q_PROPERTY(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged)
Q_PROPERTY(bool px4Firmware READ px4Firmware CONSTANT)
Q_PROPERTY(bool apmFirmware READ apmFirmware CONSTANT)
Q_PROPERTY(bool genericFirmware READ genericFirmware CONSTANT)
/// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
......@@ -253,9 +256,14 @@ public:
int satelliteLock () { return _satelliteLock; }
unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; }
int rcRSSI () { return _rcRSSI; }
bool px4Firmware () { return _firmwareType == MAV_AUTOPILOT_PX4; }
bool apmFirmware () { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
bool genericFirmware () { return !px4Firmware() && !apmFirmware(); }
ParameterLoader* getParameterLoader(void);
static const int cMaxRcChannels = 18;
public slots:
void setLatitude(double latitude);
void setLongitude(double longitude);
......@@ -305,6 +313,14 @@ signals:
void flowImageIndexChanged ();
void rcRSSIChanged (int rcRSSI);
/// New RC channel values
/// @param channelCount Number of available channels, cMaxRcChannels max
/// @param pwmValues -1 signals channel not available
void rcChannelsChanged(int channelCount, int pwmValues[cMaxRcChannels]);
/// Remote control RSSI changed (0% - 100%)
void remoteControlRSSIChanged(uint8_t rssi);
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
void _linkInactiveOrDeleted(LinkInterface* link);
......@@ -342,6 +358,8 @@ private:
void _startJoystick(bool start);
void _handleHomePosition(mavlink_message_t& message);
void _handleHeartbeat(mavlink_message_t& message);
void _handleRCChannels(mavlink_message_t& message);
void _handleRCChannelsRaw(mavlink_message_t& message);
void _missionManagerError(int errorCode, const QString& errorMsg);
void _mapTrajectoryStart(void);
void _mapTrajectoryStop(void);
......
......@@ -171,6 +171,11 @@ public:
// Called to signal app shutdown. Disconnects all links while turning off auto-connect.
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
bool isAutoconnectLink(LinkInterface* link);
......
......@@ -929,3 +929,58 @@ void MockConfiguration::updateSettings()
}
}
}
MockLink* MockLink::_startMockLink(MockConfiguration* mockConfig)
{
LinkManager* linkManager = qgcApp()->toolbox()->linkManager();
mockConfig->setDynamic(true);
linkManager->linkConfigurations()->append(mockConfig);
return qobject_cast<MockLink*>(linkManager->createConnectedLink(mockConfig));
}
MockLink* MockLink::startPX4MockLink(bool sendStatusText)
{
MockConfiguration* mockConfig = new MockConfiguration("PX4 MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_PX4);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
return _startMockLink(mockConfig);
}
MockLink* MockLink::startGenericMockLink(bool sendStatusText)
{
MockConfiguration* mockConfig = new MockConfiguration("Generic MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
return _startMockLink(mockConfig);
}
MockLink* MockLink::startAPMArduCopterMockLink(bool sendStatusText)
{
MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
return _startMockLink(mockConfig);
}
MockLink* MockLink::startAPMArduPlaneMockLink(bool sendStatusText)
{
MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
mockConfig->setSendStatusText(sendStatusText);
return _startMockLink(mockConfig);
}
......@@ -146,6 +146,11 @@ public:
/// Reset the state of the MissionItemHandler to no items, no transactions in progress.
void resetMissionItemHandler(void) { _missionItemHandler.reset(); }
static MockLink* startPX4MockLink (bool sendStatusText);
static MockLink* startGenericMockLink (bool sendStatusText);
static MockLink* startAPMArduCopterMockLink (bool sendStatusText);
static MockLink* startAPMArduPlaneMockLink (bool sendStatusText);
signals:
/// @brief Used internally to move data to the thread.
void _incomingBytes(const QByteArray bytes);
......@@ -189,6 +194,8 @@ private:
void _sendGpsRawInt(void);
void _sendStatusTextMessages(void);
static MockLink* _startMockLink(MockConfiguration* mockConfig);
MockLinkMissionItemHandler _missionItemHandler;
QString _name;
......
......@@ -47,12 +47,11 @@ public:
RadioConfigTest(void);
private slots:
void init(void);
void cleanup(void);
void _minRCChannels_test(void);
void _fullCalibration_test(void);
void _fullCalibration_px4_test(void);
void _fullCalibration_apm_test(void);
private:
/// @brief Modes to run worker functions
enum TestMode {
......@@ -67,15 +66,6 @@ private:
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 {
validateMinMaxMask = 1 << 0,
validateTrimsMask = 1 << 1,
......@@ -85,12 +75,28 @@ private:
};
struct ChannelSettings {
int function;
int function;
int rcMin;
int rcMax;
int rcTrim;
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);
......@@ -113,12 +119,13 @@ private:
static const int _testMaxValue;
static const int _testCenterValue;
static const int _availableChannels = 18; ///< Simulate 18 channel RC Transmitter
static const int _stickSettleWait;
static const struct ChannelSettings _rgChannelSettings[_availableChannels];
static const struct ChannelSettings _rgChannelSettingsValidate[RadioComponentController::_chanMax];
static const struct ChannelSettings _rgChannelSettingsPX4[RadioComponentController::_chanMaxPX4];
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];
RadioComponentController* _controller;
......
......@@ -30,6 +30,7 @@
#include "QGCApplication.h"
#include "MAVLinkProtocol.h"
#include "MainWindow.h"
#include "Vehicle.h"
bool UnitTest::_messageBoxRespondedTo = false;
bool UnitTest::_badResponseButton = false;
......@@ -46,6 +47,7 @@ UnitTest::UnitTest(void)
: _linkManager(NULL)
, _mockLink(NULL)
, _mainWindow(NULL)
, _vehicle(NULL)
, _expectMissedFileDialog(false)
, _expectMissedMessageBox(false)
, _unitTestRun(false)
......@@ -110,6 +112,8 @@ void UnitTest::init(void)
_linkManager = qgcApp()->toolbox()->linkManager();
connect(_linkManager, &LinkManager::linkDeleted, this, &UnitTest::_linkDeleted);
}
_linkManager->restart();
_messageBoxRespondedTo = false;
_missedMessageBoxCount = 0;
......@@ -369,17 +373,27 @@ void UnitTest::_connectMockLink(MAV_AUTOPILOT autopilot)
{
Q_ASSERT(!_mockLink);
_mockLink = new MockLink();
_mockLink->setFirmwareType(autopilot);
_linkManager->_addLink(_mockLink);
_linkManager->connectLink(_mockLink);
switch (autopilot) {
case MAV_AUTOPILOT_PX4:
_mockLink = MockLink::startPX4MockLink(false);
break;
case MAV_AUTOPILOT_ARDUPILOTMEGA:
_mockLink = MockLink::startAPMArduCopterMockLink(false);
break;
case MAV_AUTOPILOT_GENERIC:
_mockLink = MockLink::startGenericMockLink(false);
break;
default:
qWarning() << "Type not supported";
break;
}
// Wait for the Vehicle to get created
QSignalSpy spyVehicle(qgcApp()->toolbox()->multiVehicleManager(), SIGNAL(parameterReadyVehicleAvailableChanged(bool)));
QCOMPARE(spyVehicle.wait(5000), true);
QVERIFY(qgcApp()->toolbox()->multiVehicleManager()->parameterReadyVehicleAvailable());
QVERIFY(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle());
_vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
QVERIFY(_vehicle);
}
void UnitTest::_disconnectMockLink(void)
......@@ -392,6 +406,8 @@ void UnitTest::_disconnectMockLink(void)
// Wait for link to go away
linkSpy.wait(1000);
QCOMPARE(linkSpy.count(), 1);
_vehicle = NULL;
}
}
......
......@@ -45,6 +45,7 @@ class QGCFileDialog;
class LinkManager;
class MockLink;
class MainWindow;
class Vehicle;
class UnitTest : public QObject
{
......@@ -115,6 +116,7 @@ protected:
LinkManager* _linkManager;
MockLink* _mockLink;
MainWindow* _mainWindow;
Vehicle* _vehicle;
bool _expectMissedFileDialog; // true: expect a missed file dialog, used for internal testing
bool _expectMissedMessageBox; // true: expect a missed message box, used for internal testing
......
......@@ -33,10 +33,11 @@
#include "MessageBoxTest.h"
#include "MissionItemTest.h"
#include "MissionControllerTest.h"
#include "PX4RCCalibrationTest.h"
#include "RadioConfigTest.h"
#include "SetupViewTest.h"
#include "MavlinkLogTest.h"
UT_REGISTER_TEST(SetupViewTest)
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
UT_REGISTER_TEST(FileDialogTest)
......@@ -48,7 +49,6 @@ UT_REGISTER_TEST(MessageBoxTest)
UT_REGISTER_TEST(MissionItemTest)
UT_REGISTER_TEST(MissionControllerTest)
UT_REGISTER_TEST(RadioConfigTest)
UT_REGISTER_TEST(SetupViewTest)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.
......
......@@ -755,82 +755,9 @@ void UAS::receiveMessage(mavlink_message_t message)
mavlink_gps_global_origin_t pos;
mavlink_msg_gps_global_origin_decode(&message, &pos);
emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0);
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
{
mavlink_rc_channels_t channels;
mavlink_msg_rc_channels_decode(&message, &channels);
emit remoteControlRSSIChanged(channels.rssi);
if (channels.chan1_raw != UINT16_MAX && channels.chancount > 0)
emit remoteControlChannelRawChanged(0, channels.chan1_raw);
if (channels.chan2_raw != UINT16_MAX && channels.chancount > 1)
emit remoteControlChannelRawChanged(1, channels.chan2_raw);
if (channels.chan3_raw != UINT16_MAX && channels.chancount > 2)
emit remoteControlChannelRawChanged(2, channels.chan3_raw);
if (channels.chan4_raw != UINT16_MAX && channels.chancount > 3)
emit remoteControlChannelRawChanged(3, channels.chan4_raw);
if (channels.chan5_raw != UINT16_MAX && channels.chancount > 4)
emit remoteControlChannelRawChanged(4, channels.chan5_raw);
if (channels.chan6_raw != UINT16_MAX && channels.chancount > 5)
emit remoteControlChannelRawChanged(5, channels.chan6_raw);
if (channels.chan7_raw != UINT16_MAX && channels.chancount > 6)
emit remoteControlChannelRawChanged(6, channels.chan7_raw);
if (channels.chan8_raw != UINT16_MAX && channels.chancount > 7)
emit remoteControlChannelRawChanged(7, channels.chan8_raw);
if (channels.chan9_raw != UINT16_MAX && channels.chancount > 8)
emit remoteControlChannelRawChanged(8, channels.chan9_raw);
if (channels.chan10_raw != UINT16_MAX && channels.chancount > 9)
emit remoteControlChannelRawChanged(9, channels.chan10_raw);
if (channels.chan11_raw != UINT16_MAX && channels.chancount > 10)
emit remoteControlChannelRawChanged(10, channels.chan11_raw);
if (channels.chan12_raw != UINT16_MAX && channels.chancount > 11)
emit remoteControlChannelRawChanged(11, channels.chan12_raw);
if (channels.chan13_raw != UINT16_MAX && channels.chancount > 12)
emit remoteControlChannelRawChanged(12, channels.chan13_raw);
if (channels.chan14_raw != UINT16_MAX && channels.chancount > 13)
emit remoteControlChannelRawChanged(13, channels.chan14_raw);
if (channels.chan15_raw != UINT16_MAX && channels.chancount > 14)
emit remoteControlChannelRawChanged(14, channels.chan15_raw);
if (channels.chan16_raw != UINT16_MAX && channels.chancount > 15)
emit remoteControlChannelRawChanged(15, channels.chan16_raw);
if (channels.chan17_raw != UINT16_MAX && channels.chancount > 16)
emit remoteControlChannelRawChanged(16, channels.chan17_raw);
if (channels.chan18_raw != UINT16_MAX && channels.chancount > 17)
emit remoteControlChannelRawChanged(17, channels.chan18_raw);
}
break;
// TODO: (gg 20150420) PX4 Firmware does not seem to send this message. Don't know what to do about it.
case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
{
mavlink_rc_channels_scaled_t channels;
mavlink_msg_rc_channels_scaled_decode(&message, &channels);
const unsigned int portWidth = 8; // XXX magic number
emit remoteControlRSSIChanged(channels.rssi);
if (static_cast<uint16_t>(channels.chan1_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 0, channels.chan1_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan2_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 1, channels.chan2_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan3_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 2, channels.chan3_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan4_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 3, channels.chan4_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan5_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 4, channels.chan5_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan6_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 5, channels.chan6_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan7_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 6, channels.chan7_scaled/10000.0f);
if (static_cast<uint16_t>(channels.chan8_scaled) != UINT16_MAX)
emit remoteControlChannelScaledChanged(channels.port * portWidth + 7, channels.chan8_scaled/10000.0f);
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE:
{
mavlink_param_value_t rawValue;
......
......@@ -302,13 +302,6 @@ signals:
/** @brief Differential pressure / airspeed status changed */
void airspeedStatusChanged(bool supported, bool enabled, bool ok);
/** @brief Value of a remote control channel (raw) */
void remoteControlChannelRawChanged(int channelId, float raw);
/** @brief Value of a remote control channel (scaled)*/
void remoteControlChannelScaledChanged(int channelId, float normalized);
/** @brief Remote control RSSI changed (0% - 100%)*/
void remoteControlRSSIChanged(uint8_t rssi);
/**
* @brief Localization quality changed
* @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
......
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