Browse Source

Mock implementation of a Link

Handy for testing without a real board
QGC4.4
Don Gagne 11 years ago
parent
commit
765222eb5e
  1. 6
      qgroundcontrol.pro
  2. 3
      qgroundcontrol.qrc
  3. 516
      src/qgcunittest/MockLink.cc
  4. 118
      src/qgcunittest/MockLink.h
  5. 438
      src/qgcunittest/MockLink.param
  6. 1178
      src/qgcunittest/MockLinkMissionItemHandler.cc
  7. 109
      src/qgcunittest/MockLinkMissionItemHandler.h
  8. 39
      src/ui/CommConfigurationWindow.cc
  9. 3
      src/ui/CommConfigurationWindow.h

6
qgroundcontrol.pro

@ -662,12 +662,16 @@ SOURCES += \ @@ -662,12 +662,16 @@ SOURCES += \
DebugBuild|WindowsDebugAndRelease {
DEFINES += UNITTEST_BUILD
INCLUDEPATH += \
src/qgcunittest
HEADERS += \
src/qgcunittest/AutoTest.h \
src/qgcunittest/UASUnitTest.h \
src/qgcunittest/MockLink.h \
src/qgcunittest/MockLinkMissionItemHandler.h \
src/qgcunittest/MockUASManager.h \
src/qgcunittest/MockUAS.h \
src/qgcunittest/MockQGCUASParamManager.h \
@ -682,6 +686,8 @@ HEADERS += \ @@ -682,6 +686,8 @@ HEADERS += \
SOURCES += \
src/qgcunittest/UASUnitTest.cc \
src/qgcunittest/MockLink.cc \
src/qgcunittest/MockLinkMissionItemHandler.cc \
src/qgcunittest/MockUASManager.cc \
src/qgcunittest/MockUAS.cc \
src/qgcunittest/MockQGCUASParamManager.cc \

3
qgroundcontrol.qrc

@ -228,4 +228,7 @@ @@ -228,4 +228,7 @@
<qresource prefix="/general">
<file alias="vera.ttf">files/styles/Vera.ttf</file>
</qresource>
<qresource prefix="/unittest">
<file alias="MockLink.param">src/qgcunittest/MockLink.param</file>
</qresource>
</RCC>

516
src/qgcunittest/MockLink.cc

@ -0,0 +1,516 @@ @@ -0,0 +1,516 @@
/*=====================================================================
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 "MockLink.h"
#include <QTimer>
#include <QDebug>
#include <QFile>
#include "LinkManager.h"
#include <string.h>
/// @file
/// @brief Mock implementation of a Link.
///
/// @author Don Gagne <don@thegagnes.com>
MockLink::MockLink(void) :
_linkId(getNextLinkId()),
_name("MockLink"),
_connected(false),
_vehicleSystemId(128), // FIXME: Pull from eventual parameter manager
_vehicleComponentId(200), // FIXME: magic number?
_inNSH(false),
_mavlinkStarted(false),
_mavMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED),
_mavState(MAV_STATE_STANDBY)
{
_missionItemHandler = new MockLinkMissionItemHandler(_vehicleSystemId, this);
Q_CHECK_PTR(_missionItemHandler);
moveToThread(this);
_loadParams();
QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
LinkManager::instance()->add(this);
}
MockLink::~MockLink(void)
{
disconnect();
deleteLater();
}
void MockLink::readBytes(void)
{
// FIXME: This is a bad virtual from LinkInterface?
}
bool MockLink::connect(void)
{
_connected = true;
start();
emit connected();
emit connected(true);
return true;
}
bool MockLink::disconnect(void)
{
_connected = false;
exit();
emit disconnected();
emit connected(false);
return true;
}
void MockLink::run(void)
{
QTimer _timer1HzTasks;
QTimer _timer10HzTasks;
QTimer _timer50HzTasks;
QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
_timer1HzTasks.start(1000);
_timer10HzTasks.start(100);
_timer50HzTasks.start(20);
exec();
emit disconnected();
emit connected(false);
}
void MockLink::_run1HzTasks(void)
{
if (_mavlinkStarted) {
_sendHeartBeat();
}
}
void MockLink::_run10HzTasks(void)
{
if (_mavlinkStarted) {
}
}
void MockLink::_run50HzTasks(void)
{
if (_mavlinkStarted) {
}
}
void MockLink::_loadParams(void)
{
QFile paramFile(":/unittest/MockLink.param");
bool success = paramFile.open(QFile::ReadOnly);
Q_UNUSED(success);
Q_ASSERT(success);
QTextStream paramStream(&paramFile);
while (!paramStream.atEnd()) {
QString line = paramStream.readLine();
if (line.startsWith("#")) {
continue;
}
QStringList paramData = line.split("\t");
Q_ASSERT(paramData.count() == 5);
QString paramName = paramData.at(2);
QString valStr = paramData.at(3);
uint paramType = paramData.at(4).toUInt();
QVariant paramValue;
switch (paramType) {
case MAV_PARAM_TYPE_REAL32:
paramValue = QVariant(valStr.toFloat());
break;
case MAV_PARAM_TYPE_UINT32:
paramValue = QVariant(valStr.toUInt());
break;
case MAV_PARAM_TYPE_INT32:
paramValue = QVariant(valStr.toInt());
break;
case MAV_PARAM_TYPE_INT8:
paramValue = QVariant((unsigned char)valStr.toUInt());
break;
default:
Q_ASSERT(false);
break;
}
_parameters[paramName] = paramValue;
}
_cParameters = _parameters.count();
}
void MockLink::_sendHeartBeat(void)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
mavlink_msg_heartbeat_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
MAV_TYPE_QUADROTOR, // MAV_TYPE
MAV_AUTOPILOT_PX4, // MAV_AUTOPILOT
_mavMode, // MAV_MODE
0, // custom mode
_mavState); // MAV_STATE
int cBuffer = mavlink_msg_to_send_buffer(buffer, &msg);
QByteArray bytes((char *)buffer, cBuffer);
emit bytesReceived(this, bytes);
}
/// @brief Called when QGC wants to write bytes to the MAV
void MockLink::writeBytes(const char* bytes, qint64 cBytes)
{
// Package up the data so we can signal it over to the right thread
QByteArray byteArray(bytes, cBytes);
emit _incomingBytes(byteArray);
}
/// @brief Handles bytes from QGC on the thread
void MockLink::_handleIncomingBytes(const QByteArray bytes)
{
if (_inNSH) {
_handleIncomingNSHBytes(bytes.constData(), bytes.count());
} else {
if (bytes.startsWith(QByteArray("\r\r\r"))) {
_inNSH = true;
_handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
}
_handleIncomingMavlinkBytes((uint8_t *)bytes.constData(), bytes.count());
}
}
/// @brief Handle incoming bytes which are meant to be interpreted by the NuttX shell
void MockLink::_handleIncomingNSHBytes(const char* bytes, int cBytes)
{
Q_UNUSED(cBytes);
// Drop back out of NSH
if (cBytes == 4 && bytes[0] == '\r' && bytes[1] == '\r' && bytes[2] == '\r') {
_inNSH = false;
return;
}
if (cBytes > 0) {
qDebug() << "NSH:" << (const char*)bytes;
if (strncmp(bytes, "sh /etc/init.d/rc.usb\n", cBytes) == 0) {
// This is the mavlink start command
_mavlinkStarted = true;
}
}
}
/// @brief Handle incoming bytes which are meant to be handled by the mavlink protocol
void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
{
mavlink_message_t msg;
mavlink_status_t comm;
for (qint64 i=0; i<cBytes; i++)
{
if (!mavlink_parse_char(_linkId, bytes[i], &msg, &comm)) {
continue;
}
Q_ASSERT(_missionItemHandler);
_missionItemHandler->handleMessage(msg);
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartBeat(msg);
break;
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
_handleParamRequestList(msg);
break;
case MAVLINK_MSG_ID_SET_MODE:
_handleSetMode(msg);
break;
case MAVLINK_MSG_ID_PARAM_SET:
_handleParamSet(msg);
break;
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
_handleParamRequestRead(msg);
break;
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
_handleMissionRequestList(msg);
break;
case MAVLINK_MSG_ID_MISSION_REQUEST:
_handleMissionRequest(msg);
break;
case MAVLINK_MSG_ID_MISSION_ITEM:
_handleMissionItem(msg);
break;
#if 0
case MAVLINK_MSG_ID_MISSION_COUNT:
_handleMissionCount(msg);
break;
#endif
default:
qDebug() << "MockLink: Unhandled mavlink message, id:" << msg.msgid;
break;
}
}
}
void MockLink::_emitMavlinkMessage(const mavlink_message_t& msg)
{
uint8_t outputBuffer[MAVLINK_MAX_PACKET_LEN];
int cBuffer = mavlink_msg_to_send_buffer(outputBuffer, &msg);
QByteArray bytes((char *)outputBuffer, cBuffer);
emit bytesReceived(this, bytes);
}
void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
Q_UNUSED(msg);
#if 0
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&msg, &heartbeat);
#endif
}
void MockLink::_handleSetMode(const mavlink_message_t& msg)
{
mavlink_set_mode_t request;
mavlink_msg_set_mode_decode(&msg, &request);
if (request.target_system == _vehicleSystemId) {
_mavMode = request.base_mode;
} else {
_errorInvalidTargetSystem(request.target_system);
}
}
void MockLink::_errorInvalidTargetSystem(int targetId)
{
QString errMsg("MSG_ID_SET_MODE received incorrect target system: actual(%1) expected(%2)");
emit error(errMsg.arg(targetId).arg(_vehicleSystemId));
}
void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
mavlink_param_request_list_t request;
mavlink_msg_param_request_list_decode(&msg, &request);
uint16_t paramIndex = 0;
if (request.target_system == _vehicleSystemId) {
ParamMap_t::iterator param;
for (param = _parameters.begin(); param != _parameters.end(); param++) {
mavlink_message_t responseMsg;
mavlink_msg_param_value_pack(_vehicleSystemId,
_vehicleComponentId,
&responseMsg, // Outgoing message
param.key().toLocal8Bit().constData(), // Parameter name
param.value().toFloat(), // Parameter vluae
MAV_PARAM_TYPE_REAL32, // FIXME: Pull from QVariant type
_cParameters, // Total number of parameters
paramIndex++); // Index of this parameter
_emitMavlinkMessage(responseMsg);
}
} else {
_errorInvalidTargetSystem(request.target_system);
}
}
void MockLink::_handleParamSet(const mavlink_message_t& msg)
{
mavlink_param_set_t request;
mavlink_msg_param_set_decode(&msg, &request);
if (request.target_system == _vehicleSystemId) {
// Param may not be null terminated if exactly fits
char paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
if (_parameters.contains(paramId))
{
_parameters[paramId] = request.param_value;
mavlink_message_t responseMsg;
mavlink_msg_param_value_pack(_vehicleSystemId,
_vehicleComponentId,
&responseMsg, // Outgoing message
paramId, // Parameter name
request.param_value, // Parameter vluae
MAV_PARAM_TYPE_REAL32, // FIXME: Pull from QVariant type
_cParameters, // Total number of parameters
_parameters.keys().indexOf(paramId)); // Index of this parameter
_emitMavlinkMessage(responseMsg);
} else {
QString errMsg("MSG_ID_PARAM_SET requested unknown param id (%1)");
emit error(errMsg.arg(paramId));
}
} else {
_errorInvalidTargetSystem(request.target_system);
}
}
void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
mavlink_param_request_read_t request;
mavlink_msg_param_request_read_decode(&msg, &request);
char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
paramId[0] = 0;
if (request.target_system == _vehicleSystemId) {
if (request.param_index == -1) {
// Request is by param name. Param may not be null terminated if exactly fits
strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
} else {
if (request.param_index >= 0 && request.param_index < _cParameters) {
// Request is by index
QString key = _parameters.keys().at(request.param_index);
Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
strcpy(paramId, key.toLocal8Bit().constData());
} else {
QString errMsg("MSG_ID_PARAM_REQUEST_READ requested unknown index: requested(%1) count(%2)");
emit error(errMsg.arg(request.param_index).arg(_cParameters));
}
}
if (paramId[0] && _parameters.contains(paramId)) {
float paramValue = _parameters[paramId].toFloat();
mavlink_message_t responseMsg;
mavlink_msg_param_value_pack(_vehicleSystemId,
_vehicleComponentId,
&responseMsg, // Outgoing message
paramId, // Parameter name
paramValue, // Parameter vluae
MAV_PARAM_TYPE_REAL32, // FIXME: Pull from QVariant type
_cParameters, // Total number of parameters
_parameters.keys().indexOf(paramId)); // Index of this parameter
_emitMavlinkMessage(responseMsg);
}
} else {
_errorInvalidTargetSystem(request.target_system);
}
}
void MockLink::_handleMissionRequestList(const mavlink_message_t& msg)
{
mavlink_mission_request_list_t request;
mavlink_msg_mission_request_list_decode(&msg, &request);
if (request.target_system == _vehicleSystemId) {
mavlink_message_t responseMsg;
mavlink_msg_mission_count_pack(_vehicleSystemId,
_vehicleComponentId,
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
msg.compid, // Target is original sender
_missionItems.count()); // Number of mission items
_emitMavlinkMessage(responseMsg);
} else {
_errorInvalidTargetSystem(request.target_system);
}
}
void MockLink::_handleMissionRequest(const mavlink_message_t& msg)
{
mavlink_mission_request_t request;
mavlink_msg_mission_request_decode(&msg, &request);
if (request.target_system == _vehicleSystemId) {
if (request.seq >= 0 && request.seq < _missionItems.count()) {
mavlink_message_t responseMsg;
mavlink_mission_item_t item = _missionItems[request.seq];
mavlink_msg_mission_item_pack(_vehicleSystemId,
_vehicleComponentId,
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
msg.compid, // Target is original sender
request.seq, // Index of mission item being sent
item.frame,
item.command,
item.current,
item.autocontinue,
item.param1, item.param2, item.param3, item.param4,
item.x, item.y, item.z);
_emitMavlinkMessage(responseMsg);
} else {
QString errMsg("MSG_ID_MISSION_REQUEST requested unknown sequence number: requested(%1) count(%2)");
emit error(errMsg.arg(request.seq).arg(_missionItems.count()));
}
} else {
_errorInvalidTargetSystem(request.target_system);
}
}
void MockLink::_handleMissionItem(const mavlink_message_t& msg)
{
mavlink_mission_item_t request;
mavlink_msg_mission_item_decode(&msg, &request);
if (request.target_system == _vehicleSystemId) {
// FIXME: What do you do with duplication sequence numbers?
Q_ASSERT(!_missionItems.contains(request.seq));
_missionItems[request.seq] = request;
} else {
_errorInvalidTargetSystem(request.target_system);
}
}

118
src/qgcunittest/MockLink.h

@ -0,0 +1,118 @@ @@ -0,0 +1,118 @@
/*=====================================================================
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 MOCKLINK_H
#define MOCKLINK_H
#include <QMap>
#include "MockLinkMissionItemHandler.h"
#include "LinkInterface.h"
#include "mavlink.h"
/// @file
/// @brief Mock implementation of a Link.
///
/// @author Don Gagne <don@thegagnes.com>
class MockLink : public LinkInterface
{
Q_OBJECT
public:
MockLink(void);
~MockLink(void);
// Virtuals from LinkInterface
virtual int getId(void) const { return _linkId; }
virtual QString getName(void) const { return _name; }
virtual void requestReset(void){ }
virtual bool isConnected(void) const { return _connected; }
virtual qint64 getConnectionSpeed(void) const { return 100000000; }
virtual bool connect(void);
virtual bool disconnect(void);
virtual qint64 bytesAvailable(void) { return 0; }
signals:
void error(const QString& errorMsg);
/// @brief Used internally to move data to the thread.
void _incomingBytes(const QByteArray bytes);
public slots:
virtual void writeBytes(const char *bytes, qint64 cBytes);
protected slots:
// FIXME: This should not be part of LinkInterface. It is an internal link implementation detail.
virtual void readBytes(void);
private slots:
void _run1HzTasks(void);
void _run10HzTasks(void);
void _run50HzTasks(void);
private:
// QThread override
virtual void run(void);
// MockLink methods
void _sendHeartBeat(void);
void _handleIncomingBytes(const QByteArray bytes);
void _handleIncomingNSHBytes(const char* bytes, int cBytes);
void _handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes);
void _loadParams(void);
void _errorInvalidTargetSystem(int targetId);
void _emitMavlinkMessage(const mavlink_message_t& msg);
void _handleHeartBeat(const mavlink_message_t& msg);
void _handleSetMode(const mavlink_message_t& msg);
void _handleParamRequestList(const mavlink_message_t& msg);
void _handleParamSet(const mavlink_message_t& msg);
void _handleParamRequestRead(const mavlink_message_t& msg);
void _handleMissionRequestList(const mavlink_message_t& msg);
void _handleMissionRequest(const mavlink_message_t& msg);
void _handleMissionItem(const mavlink_message_t& msg);
MockLinkMissionItemHandler* _missionItemHandler;
int _linkId;
QString _name;
bool _connected;
uint8_t _vehicleSystemId;
uint8_t _vehicleComponentId;
bool _inNSH;
bool _mavlinkStarted;
typedef QMap<QString, QVariant> ParamMap_t;
ParamMap_t _parameters;
uint16_t _cParameters;
typedef QMap<uint16_t, mavlink_mission_item_t> MissionList_t;
MissionList_t _missionItems;
uint8_t _mavMode;
uint8_t _mavState;
};
#endif

438
src/qgcunittest/MockLink.param

@ -0,0 +1,438 @@ @@ -0,0 +1,438 @@
# Onboard parameters for system MAV 001
#
# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)
1 50 ATT_ACC_COMP 2 6
1 50 ATT_MAG_DECL 0 9
1 50 BAT_CAPACITY -1 9
1 50 BAT_C_SCALING 0.0124 9
1 50 BAT_N_CELLS 3 6
1 50 BAT_V_CHARGED 4.2 9
1 50 BAT_V_EMPTY 3.4 9
1 50 BAT_V_LOAD_DROP 0.07 9
1 50 BAT_V_SCALE_IO 10000 6
1 50 BAT_V_SCALING 0.0082 9
1 50 BD_GPROPERTIES 0.03 9
1 50 BD_OBJ_CD 0.1 9
1 50 BD_OBJ_MASS 0.6 9
1 50 BD_OBJ_SURFACE 0.00311725 9
1 50 BD_PRECISION 30 9
1 50 BD_TURNRADIUS 120 9
1 50 CBRK_AIRSPD_CHK 0 6
1 50 CBRK_ENGINEFAIL 284953 6
1 50 CBRK_FLIGHTTERM 121212 6
1 50 CBRK_GPSFAIL 240024 6
1 50 CBRK_IO_SAFETY 0 6
1 50 CBRK_NO_VISION 0 6
1 50 CBRK_RATE_CTRL 0 6
1 50 CBRK_SUPPLY_CHK 0 6
1 50 COM_DL_LOSS_EN 0 6
1 50 COM_DL_LOSS_T 10 6
1 50 COM_DL_REG_T 0 6
1 50 COM_EF_C2T 5 9
1 50 COM_EF_THROT 0.5 9
1 50 COM_EF_TIME 10 9
1 50 COM_RC_LOSS_T 0.5 9
1 50 EKF_ATT_V3_Q0 0.0001 9
1 50 EKF_ATT_V3_Q1 0.08 9
1 50 EKF_ATT_V3_Q2 0.009 9
1 50 EKF_ATT_V3_Q3 0.005 9
1 50 EKF_ATT_V3_Q4 0 9
1 50 EKF_ATT_V4_R0 0.0008 9
1 50 EKF_ATT_V4_R1 10000 9
1 50 EKF_ATT_V4_R2 100 9
1 50 EKF_ATT_V4_R3 0 9
1 50 FPE_DEBUG 0 6
1 50 FPE_LO_THRUST 0.4 9
1 50 FPE_SONAR_LP_L 0.2 9
1 50 FPE_SONAR_LP_U 0.5 9
1 50 FW_AIRSPD_MAX 50 9
1 50 FW_AIRSPD_MIN 13 9
1 50 FW_AIRSPD_TRIM 20 9
1 50 FW_ATT_TC 0.5 9
1 50 FW_CLMBOUT_DIFF 25 9
1 50 FW_FLARE_PMAX 15 9
1 50 FW_FLARE_PMIN 2.5 9
1 50 FW_L1_DAMPING 0.75 9
1 50 FW_L1_PERIOD 25 9
1 50 FW_LND_ANG 5 9
1 50 FW_LND_FLALT 8 9
1 50 FW_LND_HHDIST 15 9
1 50 FW_LND_HVIRT 10 9
1 50 FW_LND_TLALT -1 9
1 50 FW_LND_USETER 0 6
1 50 FW_MAN_P_MAX 45 9
1 50 FW_MAN_R_MAX 45 9
1 50 FW_PR_FF 0.4 9
1 50 FW_PR_I 0 9
1 50 FW_PR_IMAX 0.2 9
1 50 FW_PR_P 0.05 9
1 50 FW_PSP_OFF 0 9
1 50 FW_P_LIM_MAX 45 9
1 50 FW_P_LIM_MIN -45 9
1 50 FW_P_RMAX_NEG 0 9
1 50 FW_P_RMAX_POS 0 9
1 50 FW_P_ROLLFF 0 9
1 50 FW_RR_FF 0.3 9
1 50 FW_RR_I 0 9
1 50 FW_RR_IMAX 0.2 9
1 50 FW_RR_P 0.05 9
1 50 FW_RSP_OFF 0 9
1 50 FW_R_LIM 45 9
1 50 FW_R_RMAX 0 9
1 50 FW_THR_CRUISE 0.7 9
1 50 FW_THR_LND_MAX 1 9
1 50 FW_THR_MAX 1 9
1 50 FW_THR_MIN 0 9
1 50 FW_THR_SLEW_MAX 0 9
1 50 FW_T_CLMB_MAX 5 9
1 50 FW_T_HGT_OMEGA 3 9
1 50 FW_T_HRATE_FF 0 9
1 50 FW_T_HRATE_P 0.05 9
1 50 FW_T_INTEG_GAIN 0.1 9
1 50 FW_T_PTCH_DAMP 0 9
1 50 FW_T_RLL2THR 10 9
1 50 FW_T_SINK_MAX 5 9
1 50 FW_T_SINK_MIN 2 9
1 50 FW_T_SPDWEIGHT 1 9
1 50 FW_T_SPD_OMEGA 2 9
1 50 FW_T_SRATE_P 0.05 9
1 50 FW_T_THRO_CONST 8 9
1 50 FW_T_THR_DAMP 0.5 9
1 50 FW_T_TIME_CONST 5 9
1 50 FW_T_VERT_ACC 7 9
1 50 FW_YCO_VMIN 1000 9
1 50 FW_YR_FF 0.3 9
1 50 FW_YR_I 0 9
1 50 FW_YR_IMAX 0.2 9
1 50 FW_YR_P 0.05 9
1 50 FW_Y_RMAX 0 9
1 50 GF_ALTMODE 0 6
1 50 GF_COUNT -1 6
1 50 GF_ON 1 6
1 50 GF_SOURCE 0 6
1 50 INAV_DELAY_GPS 0.2 9
1 50 INAV_FLOW_K 0.15 9
1 50 INAV_FLOW_Q_MIN 0.5 9
1 50 INAV_LAND_DISP 0.7 9
1 50 INAV_LAND_T 3 9
1 50 INAV_LAND_THR 0.2 9
1 50 INAV_SONAR_ERR 0.5 9
1 50 INAV_SONAR_FILT 0.05 9
1 50 INAV_W_ACC_BIAS 0.05 9
1 50 INAV_W_GPS_FLOW 0.1 9
1 50 INAV_W_XY_FLOW 5 9
1 50 INAV_W_XY_GPS_P 1 9
1 50 INAV_W_XY_GPS_V 2 9
1 50 INAV_W_XY_RES_V 0.5 9
1 50 INAV_W_XY_VIS_P 5 9
1 50 INAV_W_XY_VIS_V 0 9
1 50 INAV_W_Z_BARO 0.5 9
1 50 INAV_W_Z_GPS_P 0.005 9
1 50 INAV_W_Z_SONAR 3 9
1 50 INAV_W_Z_VIS_P 0.5 9
1 50 LAUN_ALL_ON 0 6
1 50 LAUN_CAT_A 30 9
1 50 LAUN_CAT_MDEL 0 9
1 50 LAUN_CAT_PMAX 30 9
1 50 LAUN_CAT_T 0.05 9
1 50 LAUN_THR_PRE 0 9
1 50 MAV_COMP_ID 50 6
1 50 MAV_FWDEXTSP 1 6
1 50 MAV_SYS_ID 128 6
1 50 MAV_TYPE 2 6
1 50 MAV_USEHILGPS 0 6
1 50 MC_ACRO_P_MAX 90 9
1 50 MC_ACRO_R_MAX 90 9
1 50 MC_ACRO_Y_MAX 120 9
1 50 MC_MAN_P_MAX 35 9
1 50 MC_MAN_R_MAX 35 9
1 50 MC_MAN_Y_MAX 120 9
1 50 MC_PITCHRATE_D 0.003 9
1 50 MC_PITCHRATE_I 0 9
1 50 MC_PITCHRATE_P 0.1 9
1 50 MC_PITCH_P 7 9
1 50 MC_ROLLRATE_D 0.003 9
1 50 MC_ROLLRATE_I 0 9
1 50 MC_ROLLRATE_P 0.1 9
1 50 MC_ROLL_P 7 9
1 50 MC_YAWRATE_D 0 9
1 50 MC_YAWRATE_I 0.1 9
1 50 MC_YAWRATE_MAX 120 9
1 50 MC_YAWRATE_P 0.2 9
1 50 MC_YAW_FF 0.5 9
1 50 MC_YAW_P 2.8 9
1 50 MIS_ALTMODE 0 6
1 50 MIS_DIST_1WP 500 9
1 50 MIS_ONBOARD_EN 1 6
1 50 MIS_TAKEOFF_ALT 10 9
1 50 MPC_LAND_SPEED 1 9
1 50 MPC_THR_MAX 1 9
1 50 MPC_THR_MIN 0.1 9
1 50 MPC_TILTMAX_AIR 45 9
1 50 MPC_TILTMAX_LND 15 9
1 50 MPC_XY_FF 0.5 9
1 50 MPC_XY_P 1 9
1 50 MPC_XY_VEL_D 0.01 9
1 50 MPC_XY_VEL_I 0.02 9
1 50 MPC_XY_VEL_MAX 5 9
1 50 MPC_XY_VEL_P 0.1 9
1 50 MPC_Z_FF 0.5 9
1 50 MPC_Z_P 1 9
1 50 MPC_Z_VEL_D 0 9
1 50 MPC_Z_VEL_I 0.02 9
1 50 MPC_Z_VEL_MAX 3 9
1 50 MPC_Z_VEL_P 0.1 9
1 50 MT_ACC_D 0 9
1 50 MT_ACC_D_LP 0.5 9
1 50 MT_ACC_MAX 40 9
1 50 MT_ACC_MIN -40 9
1 50 MT_ACC_P 0.3 9
1 50 MT_AD_LP 0.5 9
1 50 MT_ALT_LP 1 9
1 50 MT_A_LP 0.5 9
1 50 MT_ENABLED 0 6
1 50 MT_FPA_D 0 9
1 50 MT_FPA_D_LP 1 9
1 50 MT_FPA_LP 1 9
1 50 MT_FPA_MAX 30 9
1 50 MT_FPA_MIN -20 9
1 50 MT_FPA_P 0.3 9
1 50 MT_LND_PIT_MAX 15 9
1 50 MT_LND_PIT_MIN -5 9
1 50 MT_LND_THR_MAX 0 9
1 50 MT_LND_THR_MIN 0 9
1 50 MT_PIT_FF 0.4 9
1 50 MT_PIT_I 0.03 9
1 50 MT_PIT_I_MAX 10 9
1 50 MT_PIT_MAX 20 9
1 50 MT_PIT_MIN -45 9
1 50 MT_PIT_OFF 0 9
1 50 MT_PIT_P 0.03 9
1 50 MT_THR_FF 0.7 9
1 50 MT_THR_I 0.25 9
1 50 MT_THR_I_MAX 10 9
1 50 MT_THR_MAX 1 9
1 50 MT_THR_MIN 0 9
1 50 MT_THR_OFF 0.7 9
1 50 MT_THR_P 0.1 9
1 50 MT_TKF_PIT_MAX 45 9
1 50 MT_TKF_PIT_MIN 0 9
1 50 MT_TKF_THR_MAX 1 9
1 50 MT_TKF_THR_MIN 1 9
1 50 MT_USP_PIT_MAX 0 9
1 50 MT_USP_PIT_MIN -45 9
1 50 MT_USP_THR_MAX 1 9
1 50 MT_USP_THR_MIN 1 9
1 50 NAV_ACC_RAD 25 9
1 50 NAV_AH_ALT 600 9
1 50 NAV_AH_LAT -265847810 6
1 50 NAV_AH_LON 1518423250 6
1 50 NAV_DLL_AH_T 120 9
1 50 NAV_DLL_CHSK 0 6
1 50 NAV_DLL_CH_ALT 600 9
1 50 NAV_DLL_CH_LAT -266072120 6
1 50 NAV_DLL_CH_LON 1518453890 6
1 50 NAV_DLL_CH_T 120 9
1 50 NAV_DLL_N 2 6
1 50 NAV_DLL_OBC 0 6
1 50 NAV_GPSF_LT 30 9
1 50 NAV_GPSF_P 0 9
1 50 NAV_GPSF_R 15 9
1 50 NAV_GPSF_TR 0.7 9
1 50 NAV_LOITER_RAD 50 9
1 50 NAV_RCL_LT 120 9
1 50 NAV_RCL_OBC 0 6
1 50 PE_ABIAS_PNOISE 5e-05 9
1 50 PE_ACC_PNOISE 0.25 9
1 50 PE_EAS_NOISE 1.4 9
1 50 PE_GBIAS_PNOISE 1e-07 9
1 50 PE_GPS_ALT_WGT 0.9 9
1 50 PE_GYRO_PNOISE 0.015 9
1 50 PE_HGT_DELAY_MS 350 6
1 50 PE_MAGB_PNOISE 0.0003 9
1 50 PE_MAGE_PNOISE 0.0003 9
1 50 PE_MAG_DELAY_MS 30 6
1 50 PE_MAG_NOISE 0.05 9
1 50 PE_POSDEV_INIT 5 9
1 50 PE_POSD_NOISE 1 9
1 50 PE_POSNE_NOISE 0.5 9
1 50 PE_POS_DELAY_MS 210 6
1 50 PE_TAS_DELAY_MS 210 6
1 50 PE_VELD_NOISE 0.7 9
1 50 PE_VELNE_NOISE 0.5 9
1 50 PE_VEL_DELAY_MS 230 6
1 50 RC10_DZ 0 9
1 50 RC10_MAX 2000 9
1 50 RC10_MIN 1000 9
1 50 RC10_REV 1 9
1 50 RC10_TRIM 1500 9
1 50 RC11_DZ 0 9
1 50 RC11_MAX 2000 9
1 50 RC11_MIN 1000 9
1 50 RC11_REV 1 9
1 50 RC11_TRIM 1500 9
1 50 RC12_DZ 0 9
1 50 RC12_MAX 2000 9
1 50 RC12_MIN 1000 9
1 50 RC12_REV 1 9
1 50 RC12_TRIM 1500 9
1 50 RC13_DZ 0 9
1 50 RC13_MAX 2000 9
1 50 RC13_MIN 1000 9
1 50 RC13_REV 1 9
1 50 RC13_TRIM 1500 9
1 50 RC14_DZ 0 9
1 50 RC14_MAX 2000 9
1 50 RC14_MIN 1000 9
1 50 RC14_REV 1 9
1 50 RC14_TRIM 1500 9
1 50 RC15_DZ 0 9
1 50 RC15_MAX 2000 9
1 50 RC15_MIN 1000 9
1 50 RC15_REV 1 9
1 50 RC15_TRIM 1500 9
1 50 RC16_DZ 0 9
1 50 RC16_MAX 2000 9
1 50 RC16_MIN 1000 9
1 50 RC16_REV 1 9
1 50 RC16_TRIM 1500 9
1 50 RC17_DZ 0 9
1 50 RC17_MAX 2000 9
1 50 RC17_MIN 1000 9
1 50 RC17_REV 1 9
1 50 RC17_TRIM 1500 9
1 50 RC18_DZ 0 9
1 50 RC18_MAX 2000 9
1 50 RC18_MIN 1000 9
1 50 RC18_REV 1 9
1 50 RC18_TRIM 1500 9
1 50 RC1_DZ 10 9
1 50 RC1_MAX 1900 9
1 50 RC1_MIN 1100 9
1 50 RC1_REV -1 9
1 50 RC1_TRIM 1490 9
1 50 RC2_DZ 10 9
1 50 RC2_MAX 1900 9
1 50 RC2_MIN 1100 9
1 50 RC2_REV 1 9
1 50 RC2_TRIM 1483 9
1 50 RC3_DZ 10 9
1 50 RC3_MAX 1901 9
1 50 RC3_MIN 1099 9
1 50 RC3_REV 1 9
1 50 RC3_TRIM 1099 9
1 50 RC4_DZ 10 9
1 50 RC4_MAX 1900 9
1 50 RC4_MIN 1100 9
1 50 RC4_REV -1 9
1 50 RC4_TRIM 1500 9
1 50 RC5_DZ 10 9
1 50 RC5_MAX 1901 9
1 50 RC5_MIN 1099 9
1 50 RC5_REV 1 9
1 50 RC5_TRIM 1500 9
1 50 RC6_DZ 10 9
1 50 RC6_MAX 1901 9
1 50 RC6_MIN 1099 9
1 50 RC6_REV 1 9
1 50 RC6_TRIM 1500 9
1 50 RC7_DZ 10 9
1 50 RC7_MAX 1901 9
1 50 RC7_MIN 1099 9
1 50 RC7_REV 1 9
1 50 RC7_TRIM 1500 9
1 50 RC8_DZ 10 9
1 50 RC8_MAX 1901 9
1 50 RC8_MIN 1099 9
1 50 RC8_REV 1 9
1 50 RC8_TRIM 1500 9
1 50 RC9_DZ 0 9
1 50 RC9_MAX 2000 9
1 50 RC9_MIN 1000 9
1 50 RC9_REV 1 9
1 50 RC9_TRIM 1500 9
1 50 RC_ACRO_TH 0.5 9
1 50 RC_ASSIST_TH 0.25 9
1 50 RC_AUTO_TH 0.75 9
1 50 RC_DSM_BIND -1 6
1 50 RC_FAILS_THR 0 6
1 50 RC_LOITER_TH 0.5 9
1 50 RC_MAP_ACRO_SW 0 6
1 50 RC_MAP_AUX1 0 6
1 50 RC_MAP_AUX2 0 6
1 50 RC_MAP_AUX3 0 6
1 50 RC_MAP_FAILSAFE 0 6
1 50 RC_MAP_FLAPS 0 6
1 50 RC_MAP_LOITER_SW 0 6
1 50 RC_MAP_MODE_SW 0 6
1 50 RC_MAP_OFFB_SW 0 6
1 50 RC_MAP_PITCH 2 6
1 50 RC_MAP_POSCTL_SW 0 6
1 50 RC_MAP_RETURN_SW 0 6
1 50 RC_MAP_ROLL 1 6
1 50 RC_MAP_THROTTLE 3 6
1 50 RC_MAP_YAW 4 6
1 50 RC_OFFB_TH 0.5 9
1 50 RC_POSCTL_TH 0.5 9
1 50 RC_RETURN_TH 0.5 9
1 50 RTL_DESCEND_ALT 20 9
1 50 RTL_LAND_DELAY -1 9
1 50 RTL_LOITER_RAD 50 9
1 50 RTL_RETURN_ALT 100 9
1 50 SDLOG_EXT -1 6
1 50 SDLOG_RATE -1 6
1 50 SENS_ACC_XOFF 0 9
1 50 SENS_ACC_XSCALE 1 9
1 50 SENS_ACC_YOFF 0 9
1 50 SENS_ACC_YSCALE 1 9
1 50 SENS_ACC_ZOFF 0 9
1 50 SENS_ACC_ZSCALE 1 9
1 50 SENS_BARO_QNH 1013.25 9
1 50 SENS_BOARD_ROT 0 6
1 50 SENS_BOARD_X_OFF 0 9
1 50 SENS_BOARD_Y_OFF 0 9
1 50 SENS_BOARD_Z_OFF 0 9
1 50 SENS_DPRES_ANSC 0 9
1 50 SENS_DPRES_OFF 0 9
1 50 SENS_EXT_MAG 0 6
1 50 SENS_EXT_MAG_ROT 0 6
1 50 SENS_GYRO_XOFF 0 9
1 50 SENS_GYRO_XSCALE 1 9
1 50 SENS_GYRO_YOFF 0 9
1 50 SENS_GYRO_YSCALE 1 9
1 50 SENS_GYRO_ZOFF 0 9
1 50 SENS_GYRO_ZSCALE 1 9
1 50 SENS_MAG_XOFF 0 9
1 50 SENS_MAG_XSCALE 1 9
1 50 SENS_MAG_YOFF 0 9
1 50 SENS_MAG_YSCALE 1 9
1 50 SENS_MAG_ZOFF 0 9
1 50 SENS_MAG_ZSCALE 1 9
1 50 SO3_COMP_KI 0.05 9
1 50 SO3_COMP_KP 1 9
1 50 SO3_PITCH_OFFS 0 9
1 50 SO3_ROLL_OFFS 0 9
1 50 SO3_YAW_OFFS 0 9
1 50 SYS_AUTOCONFIG 0 6
1 50 SYS_AUTOSTART 4010 6
1 50 SYS_RESTART_TYPE 0 6
1 50 SYS_USE_IO 1 6
1 50 TEST_D 0.01 9
1 50 TEST_DEV 2 9
1 50 TEST_D_LP 10 9
1 50 TEST_HP 10 9
1 50 TEST_I 0.1 9
1 50 TEST_I_MAX 1 9
1 50 TEST_LP 10 9
1 50 TEST_MAX 1 9
1 50 TEST_MEAN 1 9
1 50 TEST_MIN -1 9
1 50 TEST_P 0.2 9
1 50 TEST_TRIM 0.5 9
1 50 TRIM_PITCH 0 9
1 50 TRIM_ROLL 0 9
1 50 TRIM_YAW 0 9
1 50 UAVCAN_BITRATE 1000000 6
1 50 UAVCAN_ENABLE 0 6
1 50 UAVCAN_NODE_ID 1 6
1 50 test 305419896 6

1178
src/qgcunittest/MockLinkMissionItemHandler.cc

File diff suppressed because it is too large Load Diff

109
src/qgcunittest/MockLinkMissionItemHandler.h

@ -0,0 +1,109 @@ @@ -0,0 +1,109 @@
/*=====================================================================
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 MOCKLINKMISSIONITEMHANDLER_H
#define MOCKLINKMISSIONITEMHANDLER_H
// FIXME: This file is a work in progress
#include <QObject>
#include <vector>
#include "MAVLinkSimulationLink.h"
#include "QGCMAVLink.h"
enum PX_WAYPOINTPLANNER_STATES {
PX_WPP_IDLE = 0,
PX_WPP_SENDLIST,
PX_WPP_SENDLIST_SENDWPS,
PX_WPP_GETLIST,
PX_WPP_GETLIST_GETWPS,
PX_WPP_GETLIST_GOTALL
};
class MockLinkMissionItemHandler : public QObject
{
Q_OBJECT
public:
MockLinkMissionItemHandler(uint16_t systemId, QObject* parent = NULL);
/// @brief Called to handle mission item related messages. All messages should be passed to this method.
/// It will handle the appropriate set.
void handleMessage(const mavlink_message_t& msg);
#if 0
signals:
void messageSent(const mavlink_message_t& msg);
protected:
MAVLinkSimulationLink* link;
bool idle; ///< indicates if the system is following the waypoints or is waiting
uint16_t current_active_wp_id; ///< id of current waypoint
bool yawReached; ///< boolean for yaw attitude reached
bool posReached; ///< boolean for position reached
uint64_t timestamp_lastoutside_orbit;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
uint64_t timestamp_firstinside_orbit;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
std::vector<mavlink_mission_item_t*> waypoints1; ///< vector1 that holds the waypoints
std::vector<mavlink_mission_item_t*> waypoints2; ///< vector2 that holds the waypoints
std::vector<mavlink_mission_item_t*>* waypoints; ///< pointer to the currently active waypoint vector
std::vector<mavlink_mission_item_t*>* waypoints_receive_buffer; ///< pointer to the receive buffer waypoint vector
PX_WAYPOINTPLANNER_STATES current_state;
uint16_t protocol_current_wp_id;
uint16_t protocol_current_count;
uint8_t protocol_current_partner_systemid;
uint8_t protocol_current_partner_compid;
uint64_t protocol_timestamp_lastaction;
unsigned int protocol_timeout;
uint64_t timestamp_last_send_setpoint;
uint8_t systemid;
uint8_t compid;
unsigned int setpointDelay;
float yawTolerance;
bool verbose;
bool debug;
bool silent;
void send_waypoint_ack(uint8_t target_systemid, uint8_t target_compid, uint8_t type);
void send_waypoint_current(uint16_t seq);
void send_setpoint(uint16_t seq);
void send_waypoint_count(uint8_t target_systemid, uint8_t target_compid, uint16_t count);
void send_waypoint(uint8_t target_systemid, uint8_t target_compid, uint16_t seq);
void send_waypoint_request(uint8_t target_systemid, uint8_t target_compid, uint16_t seq);
void send_waypoint_reached(uint16_t seq);
float distanceToSegment(uint16_t seq, float x, float y, float z);
float distanceToPoint(uint16_t seq, float x, float y, float z);
float distanceToPoint(uint16_t seq, float x, float y);
void mavlink_handler(const mavlink_message_t* msg);
#endif
private:
uint16_t _vehicleSystemId; ///< System id of this vehicle
QList<mavlink_mission_item_t> _missionItems; ///< Current set of mission itemss
};
#endif // MAVLINKSIMULATIONWAYPOINTPLANNER_H

39
src/ui/CommConfigurationWindow.cc

@ -42,6 +42,9 @@ This file is part of the QGROUNDCONTROL project @@ -42,6 +42,9 @@ This file is part of the QGROUNDCONTROL project
#include "UDPLink.h"
#include "TCPLink.h"
#include "MAVLinkSimulationLink.h"
#ifdef UNITTEST_BUILD
#include "MockLink.h"
#endif
#ifdef QGC_XBEE_ENABLED
#include "XbeeLink.h"
#include "XbeeConfigurationWindow.h"
@ -85,11 +88,16 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn @@ -85,11 +88,16 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
ui.linkType->addItem(tr("Serial"), QGC_LINK_SERIAL);
ui.linkType->addItem(tr("UDP"), QGC_LINK_UDP);
ui.linkType->addItem(tr("TCP"), QGC_LINK_TCP);
if(dynamic_cast<MAVLinkSimulationLink*>(link)) {
//Only show simulation option if already setup elsewhere as a simulation
ui.linkType->addItem(tr("Simulation"), QGC_LINK_SIMULATION);
}
#ifdef UNITTEST_BUILD
ui.linkType->addItem(tr("Mock"), QGC_LINK_MOCK);
#endif
#ifdef QGC_RTLAB_ENABLED
ui.linkType->addItem(tr("Opal-RT Link"), QGC_LINK_OPAL);
#endif
@ -144,6 +152,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn @@ -144,6 +152,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
ui.linkGroupBox->setTitle(tr("Serial Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_SERIAL));
}
UDPLink* udp = dynamic_cast<UDPLink*>(link);
if (udp != 0) {
QWidget* conf = new QGCUDPLinkConfiguration(udp, this);
@ -151,6 +160,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn @@ -151,6 +160,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
ui.linkGroupBox->setTitle(tr("UDP Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_UDP));
}
TCPLink* tcp = dynamic_cast<TCPLink*>(link);
if (tcp != 0) {
QWidget* conf = new QGCTCPLinkConfiguration(tcp, this);
@ -158,12 +168,22 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn @@ -158,12 +168,22 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
ui.linkGroupBox->setTitle(tr("TCP Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_TCP));
}
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim != 0) {
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_SIMULATION));
ui.linkType->setEnabled(false); //Don't allow the user to change to a non-simulation
ui.linkGroupBox->setTitle(tr("MAVLink Simulation Link"));
}
#ifdef UNITTEST_BUILD
MockLink* mock = dynamic_cast<MockLink*>(link);
if (mock != 0) {
ui.linkGroupBox->setTitle(tr("Mock Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_MOCK));
}
#endif
#ifdef QGC_RTLAB_ENABLED
OpalLink* opal = dynamic_cast<OpalLink*>(link);
if (opal != 0) {
@ -175,6 +195,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn @@ -175,6 +195,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
ui.linkGroupBox->setTitle(tr("Opal-RT Link"));
}
#endif
#ifdef QGC_XBEE_ENABLED
XbeeLink* xbee = dynamic_cast<XbeeLink*>(link); // new Konrad
if(xbee != 0)
@ -187,7 +208,11 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn @@ -187,7 +208,11 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
connect(xbee,SIGNAL(tryConnectEnd(bool)),ui.actionConnect,SLOT(setEnabled(bool)));
}
#endif // QGC_XBEE_ENABLED
if (serial == 0 && udp == 0 && sim == 0 && tcp == 0
#ifdef UNITTEST_BUILD
&& mock == 0
#endif
#ifdef QGC_RTLAB_ENABLED
&& opal == 0
#endif
@ -258,6 +283,7 @@ void CommConfigurationWindow::setLinkType(qgc_link_t linktype) @@ -258,6 +283,7 @@ void CommConfigurationWindow::setLinkType(qgc_link_t linktype)
break;
}
#endif // QGC_XBEE_ENABLED
case QGC_LINK_UDP:
{
UDPLink *udp = new UDPLink();
@ -283,9 +309,18 @@ void CommConfigurationWindow::setLinkType(qgc_link_t linktype) @@ -283,9 +309,18 @@ void CommConfigurationWindow::setLinkType(qgc_link_t linktype)
break;
}
#endif // QGC_RTLAB_ENABLED
#ifdef UNITTEST_BUILD
case QGC_LINK_MOCK:
{
MockLink* mock = new MockLink;
tmpLink = mock;
MainWindow::instance()->addLink(tmpLink);
break;
}
#endif
default:
{
}
case QGC_LINK_SERIAL:
{
SerialLink *serial = new SerialLink();

3
src/ui/CommConfigurationWindow.h

@ -45,6 +45,9 @@ enum qgc_link_t { @@ -45,6 +45,9 @@ enum qgc_link_t {
QGC_LINK_TCP,
QGC_LINK_SIMULATION,
QGC_LINK_FORWARDING,
#ifdef UNITTEST_BUILD
QGC_LINK_MOCK,
#endif
#ifdef QGC_XBEE_ENABLED
QGC_LINK_XBEE,
#endif

Loading…
Cancel
Save