Newer
Older
/*=====================================================================
dogmaphobic
committed
QGroundControl Open Source Ground Control Station
dogmaphobic
committed
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
dogmaphobic
committed
dogmaphobic
committed
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.
dogmaphobic
committed
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.
dogmaphobic
committed
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
dogmaphobic
committed
======================================================================*/
#include "MockLink.h"
#include "QGCLoggingCategory.h"
#include <QTimer>
#include <QDebug>
#include <QFile>
#include <string.h>
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
QGC_LOGGING_CATEGORY(MockLinkVerboseLog, "MockLinkVerboseLog")
/// @file
/// @brief Mock implementation of a Link.
///
/// @author Don Gagne <don@thegagnes.com>
enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
PX4_CUSTOM_MAIN_MODE_ALTCTL,
PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
PX4_CUSTOM_MAIN_MODE_ACRO,
PX4_CUSTOM_MAIN_MODE_OFFBOARD,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
PX4_CUSTOM_SUB_MODE_AUTO_READY = 1,
PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,
PX4_CUSTOM_SUB_MODE_AUTO_LOITER,
PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
PX4_CUSTOM_SUB_MODE_AUTO_RTL,
PX4_CUSTOM_SUB_MODE_AUTO_LAND,
PX4_CUSTOM_SUB_MODE_AUTO_RTGS
};
union px4_custom_mode {
struct {
uint16_t reserved;
uint8_t main_mode;
uint8_t sub_mode;
};
uint32_t data;
float data_float;
};
float MockLink::_vehicleLatitude = 47.633033f;
float MockLink::_vehicleLongitude = -122.08794f;
float MockLink::_vehicleAltitude = 2.5f;
const char* MockConfiguration::_firmwareTypeKey = "FirmwareType";
const char* MockConfiguration::_vehicleTypeKey = "VehicleType";
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
MockLink::MockLink(MockConfiguration* config)
: _missionItemHandler(this)
, _name("MockLink")
, _connected(false)
, _vehicleSystemId(128) // FIXME: Pull from eventual parameter manager
, _vehicleComponentId(200) // FIXME: magic number?
, _inNSH(false)
, _mavlinkStarted(false)
, _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
, _mavState(MAV_STATE_STANDBY)
, _sendHomePositionDelayCount(2)
dogmaphobic
committed
_config = config;
_sendStatusText = config->sendStatusText();
union px4_custom_mode px4_cm;
px4_cm.data = 0;
px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
_mavCustomMode = px4_cm.data;
_fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
Q_CHECK_PTR(_fileServer);
_loadParams();
QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}
MockLink::~MockLink(void)
{
}
void MockLink::readBytes(void)
{
// FIXME: This is a bad virtual from LinkInterface?
}
bool MockLink::_connect(void)
if (!_connected) {
_connected = true;
start();
emit connected();
}
dogmaphobic
committed
bool MockLink::_disconnect(void)
if (_connected) {
_connected = false;
dogmaphobic
committed
return true;
}
void MockLink::run(void)
{
QTimer _timer1HzTasks;
QTimer _timer10HzTasks;
QTimer _timer50HzTasks;
dogmaphobic
committed
QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
dogmaphobic
committed
_timer1HzTasks.start(1000);
_timer10HzTasks.start(100);
_timer50HzTasks.start(20);
dogmaphobic
committed
dogmaphobic
committed
QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
_missionItemHandler.shutdown();
}
void MockLink::_run1HzTasks(void)
{
if (_mavlinkStarted && _connected) {
if (_sendHomePositionDelayCount > 0) {
// We delay home position a bit to be more realistic
_sendHomePositionDelayCount--;
} else {
_sendHomePosition();
}
if (_sendStatusText) {
_sendStatusText = false;
_sendStatusTextMessages();
}
}
}
void MockLink::_run10HzTasks(void)
{
if (_mavlinkStarted && _connected) {
}
}
void MockLink::_run50HzTasks(void)
{
if (_mavlinkStarted && _connected) {
}
}
void MockLink::_loadParams(void)
{
QFile paramFile;
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
if (_vehicleType == MAV_TYPE_FIXED_WING) {
paramFile.setFileName(":/unittest/APMArduPlaneMockLink.params");
} else {
paramFile.setFileName(":/unittest/APMArduCopterMockLink.params");
}
} else {
paramFile.setFileName(":/unittest/PX4MockLink.params");
}
dogmaphobic
committed
bool success = paramFile.open(QFile::ReadOnly);
Q_UNUSED(success);
Q_ASSERT(success);
dogmaphobic
committed
dogmaphobic
committed
while (!paramStream.atEnd()) {
QString line = paramStream.readLine();
dogmaphobic
committed
if (line.startsWith("#")) {
continue;
}
dogmaphobic
committed
QStringList paramData = line.split("\t");
Q_ASSERT(paramData.count() == 5);
dogmaphobic
committed
int componentId = paramData.at(1).toInt();
QString paramName = paramData.at(2);
QString valStr = paramData.at(3);
uint paramType = paramData.at(4).toUInt();
dogmaphobic
committed
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_UINT16:
paramValue = QVariant((quint16)valStr.toUInt());
break;
case MAV_PARAM_TYPE_INT16:
paramValue = QVariant((qint16)valStr.toInt());
break;
case MAV_PARAM_TYPE_UINT8:
paramValue = QVariant((quint8)valStr.toUInt());
break;
paramValue = QVariant((qint8)valStr.toUInt());
qCritical() << "Unknown type" << paramType;
paramValue = QVariant(valStr.toInt());
dogmaphobic
committed
qCDebug(MockLinkVerboseLog) << "Loading param" << paramName << paramValue;
dogmaphobic
committed
_mapParamName2Value[componentId][paramName] = paramValue;
_mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
}
}
void MockLink::_sendHeartBeat(void)
{
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
MAV_TYPE_QUADROTOR, // MAV_TYPE
_mavBaseMode, // MAV_MODE
_mavCustomMode, // custom mode
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
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);
dogmaphobic
committed
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);
}
dogmaphobic
committed
_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);
dogmaphobic
committed
// 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;
dogmaphobic
committed
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;
dogmaphobic
committed
if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
if (_missionItemHandler.handleMessage(msg)) {
dogmaphobic
committed
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartBeat(msg);
break;
dogmaphobic
committed
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
_handleParamRequestList(msg);
break;
dogmaphobic
committed
case MAVLINK_MSG_ID_SET_MODE:
_handleSetMode(msg);
break;
dogmaphobic
committed
case MAVLINK_MSG_ID_PARAM_SET:
_handleParamSet(msg);
break;
dogmaphobic
committed
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
_handleParamRequestRead(msg);
break;
case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
_handleFTP(msg);
break;
case MAVLINK_MSG_ID_COMMAND_LONG:
_handleCommandLong(msg);
break;
dogmaphobic
committed
default:
break;
}
}
}
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);
dogmaphobic
committed
Q_ASSERT(request.target_system == _vehicleSystemId);
dogmaphobic
committed
_mavBaseMode = request.base_mode;
_mavCustomMode = request.custom_mode;
}
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
{
mavlink_param_union_t valueUnion;
dogmaphobic
committed
Q_ASSERT(_mapParamName2Value.contains(componentId));
Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
dogmaphobic
committed
valueUnion.param_float = paramFloat;
dogmaphobic
committed
MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
dogmaphobic
committed
dogmaphobic
committed
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
case MAV_PARAM_TYPE_REAL32:
paramVariant = QVariant::fromValue(valueUnion.param_float);
break;
case MAV_PARAM_TYPE_UINT32:
paramVariant = QVariant::fromValue(valueUnion.param_uint32);
break;
case MAV_PARAM_TYPE_INT32:
paramVariant = QVariant::fromValue(valueUnion.param_int32);
break;
case MAV_PARAM_TYPE_UINT16:
paramVariant = QVariant::fromValue(valueUnion.param_uint16);
break;
case MAV_PARAM_TYPE_INT16:
paramVariant = QVariant::fromValue(valueUnion.param_int16);
break;
case MAV_PARAM_TYPE_UINT8:
paramVariant = QVariant::fromValue(valueUnion.param_uint8);
break;
case MAV_PARAM_TYPE_INT8:
paramVariant = QVariant::fromValue(valueUnion.param_int8);
break;
default:
qCritical() << "Invalid parameter type" << paramType;
paramVariant = QVariant::fromValue(valueUnion.param_int32);
break;
dogmaphobic
committed
qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
_mapParamName2Value[componentId][paramName] = paramVariant;
/// Convert from a parameter variant to the float value from mavlink_param_union_t
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
mavlink_param_union_t valueUnion;
dogmaphobic
committed
Q_ASSERT(_mapParamName2Value.contains(componentId));
Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
dogmaphobic
committed
MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
QVariant paramVar = _mapParamName2Value[componentId][paramName];
dogmaphobic
committed
case MAV_PARAM_TYPE_REAL32:
valueUnion.param_float = paramVar.toFloat();
break;
dogmaphobic
committed
case MAV_PARAM_TYPE_UINT32:
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = paramVar.toUInt();
} else {
valueUnion.param_uint32 = paramVar.toUInt();
}
break;
dogmaphobic
committed
case MAV_PARAM_TYPE_INT32:
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = paramVar.toInt();
} else {
valueUnion.param_int32 = paramVar.toInt();
}
break;
dogmaphobic
committed
case MAV_PARAM_TYPE_UINT16:
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = paramVar.toUInt();
} else {
valueUnion.param_uint16 = paramVar.toUInt();
}
break;
dogmaphobic
committed
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
case MAV_PARAM_TYPE_INT16:
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = paramVar.toInt();
} else {
valueUnion.param_int16 = paramVar.toInt();
}
break;
case MAV_PARAM_TYPE_UINT8:
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = paramVar.toUInt();
} else {
valueUnion.param_uint8 = paramVar.toUInt();
}
break;
case MAV_PARAM_TYPE_INT8:
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
} else {
valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
}
break;
default:
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = paramVar.toInt();
} else {
valueUnion.param_int32 = paramVar.toInt();
}
qCritical() << "Invalid parameter type" << paramType;
dogmaphobic
committed
return valueUnion.param_float;
}
void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
mavlink_param_request_list_t request;
dogmaphobic
committed
mavlink_msg_param_request_list_decode(&msg, &request);
dogmaphobic
committed
Q_ASSERT(request.target_system == _vehicleSystemId);
Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
// We must send the first parameter for each component first. Otherwise system won't correctly know
// when all parameters are loaded.
foreach (int componentId, _mapParamName2Value.keys()) {
int cParameters = _mapParamName2Value[componentId].count();
foreach(QString paramName, _mapParamName2Value[componentId].keys()) {
char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
mavlink_message_t responseMsg;
Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
Q_ASSERT(paramName.length() <= MAVLINK_MSG_ID_PARAM_VALUE_LEN);
strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_ID_PARAM_VALUE_LEN);
qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
mavlink_msg_param_value_pack(_vehicleSystemId,
componentId, // component id
&responseMsg, // Outgoing message
paramId, // Parameter name
_floatUnionForParam(componentId, paramName), // Parameter value
paramType, // MAV_PARAM_TYPE
cParameters, // Total number of parameters
paramIndex++); // Index of this parameter
// Only first parameter the first time through
break;
}
}
foreach (int componentId, _mapParamName2Value.keys()) {
uint16_t paramIndex = 0;
int cParameters = _mapParamName2Value[componentId].count();
bool skipParam = true;
foreach(QString paramName, _mapParamName2Value[componentId].keys()) {
if (skipParam) {
// We've already sent the first param
paramIndex++;
} else {
char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
mavlink_message_t responseMsg;
Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
Q_ASSERT(paramName.length() <= MAVLINK_MSG_ID_PARAM_VALUE_LEN);
strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_ID_PARAM_VALUE_LEN);
qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
mavlink_msg_param_value_pack(_vehicleSystemId,
componentId, // component id
&responseMsg, // Outgoing message
paramId, // Parameter name
_floatUnionForParam(componentId, paramName), // Parameter value
paramType, // MAV_PARAM_TYPE
cParameters, // Total number of parameters
paramIndex++); // Index of this parameter
}
}
void MockLink::_handleParamSet(const mavlink_message_t& msg)
{
mavlink_param_set_t request;
mavlink_msg_param_set_decode(&msg, &request);
dogmaphobic
committed
Q_ASSERT(request.target_system == _vehicleSystemId);
int componentId = request.target_component;
// 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);
dogmaphobic
committed
qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
Q_ASSERT(_mapParamName2Value.contains(componentId));
Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
dogmaphobic
committed
_setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
dogmaphobic
committed
// Respond with a param_value to ack
mavlink_message_t responseMsg;
mavlink_msg_param_value_pack(_vehicleSystemId,
componentId, // component id
&responseMsg, // Outgoing message
paramId, // Parameter name
request.param_value, // Send same value back
request.param_type, // Send same type back
_mapParamName2Value[componentId].count(), // Total number of parameters
_mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
}
void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
mavlink_message_t responseMsg;
mavlink_param_request_read_t request;
mavlink_msg_param_request_read_decode(&msg, &request);
const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
int componentId = request.target_component;
// special case for magic _HASH_CHECK value
if (request.target_component == MAV_COMP_ID_ALL && param_name == "_HASH_CHECK") {
mavlink_param_union_t valueUnion;
valueUnion.type = MAV_PARAM_TYPE_UINT32;
valueUnion.param_uint32 = 0;
// Special case of magic hash check value
mavlink_msg_param_value_pack(_vehicleSystemId,
componentId,
&responseMsg,
request.param_id,
valueUnion.param_float,
MAV_PARAM_TYPE_UINT32,
0,
-1);
respondWithMavlinkMessage(responseMsg);
return;
}
Q_ASSERT(_mapParamName2Value.contains(componentId));
dogmaphobic
committed
char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
paramId[0] = 0;
dogmaphobic
committed
Q_ASSERT(request.target_system == _vehicleSystemId);
dogmaphobic
committed
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);
dogmaphobic
committed
Q_ASSERT(request.param_index >= 0 && request.param_index < _mapParamName2Value[componentId].count());
dogmaphobic
committed
QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
strcpy(paramId, key.toLocal8Bit().constData());
Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
dogmaphobic
committed
mavlink_msg_param_value_pack(_vehicleSystemId,
componentId, // component id
&responseMsg, // Outgoing message
paramId, // Parameter name
_floatUnionForParam(componentId, paramId), // Parameter value
_mapParamName2MavParamType[paramId], // Parameter type
_mapParamName2Value[componentId].count(), // Total number of parameters
_mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
uint16_t chanRaw[18];
for (int i=0; i<18; i++) {
chanRaw[i] = UINT16_MAX;
}
chanRaw[channel] = raw;
mavlink_message_t responseMsg;
mavlink_msg_rc_channels_pack(_vehicleSystemId,
_vehicleComponentId,
&responseMsg, // Outgoing message
0, // time since boot, ignored
18, // channel count
chanRaw[0], // channel raw value
chanRaw[1], // channel raw value
chanRaw[2], // channel raw value
chanRaw[3], // channel raw value
chanRaw[4], // channel raw value
chanRaw[5], // channel raw value
chanRaw[6], // channel raw value
chanRaw[7], // channel raw value
chanRaw[8], // channel raw value
chanRaw[9], // channel raw value
chanRaw[10], // channel raw value
chanRaw[11], // channel raw value
chanRaw[12], // channel raw value
chanRaw[13], // channel raw value
chanRaw[14], // channel raw value
chanRaw[15], // channel raw value
chanRaw[16], // channel raw value
chanRaw[17], // channel raw value
0); // rss
respondWithMavlinkMessage(responseMsg);
}
void MockLink::_handleFTP(const mavlink_message_t& msg)
{
Q_ASSERT(_fileServer);
_fileServer->handleFTPMessage(msg);
void MockLink::_handleCommandLong(const mavlink_message_t& msg)
{
mavlink_command_long_t request;
mavlink_msg_command_long_decode(&msg, &request);
if (request.command == MAV_CMD_COMPONENT_ARM_DISARM) {
if (request.param1 == 0.0f) {
_mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
} else {
_mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
}
}
}
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly)
{
_missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
}
void MockLink::_sendHomePosition(void)
{
// APM stack does not yet support HOME_POSITION
if (_firmwareType != MAV_AUTOPILOT_ARDUPILOTMEGA) {
mavlink_message_t msg;
float bogus[4];
bogus[0] = 0.0f;
bogus[1] = 0.0f;
bogus[2] = 0.0f;
bogus[3] = 0.0f;
mavlink_msg_home_position_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
(int32_t)(_vehicleLatitude * 1E7),
(int32_t)(_vehicleLongitude * 1E7),
(int32_t)(_vehicleAltitude * 1000),
0.0f, 0.0f, 0.0f,
&bogus[0],
0.0f, 0.0f, 0.0f);
respondWithMavlinkMessage(msg);
}
void MockLink::_sendGpsRawInt(void)
{
static uint64_t timeTick = 0;
mavlink_message_t msg;
mavlink_msg_gps_raw_int_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
timeTick++, // time since boot
3, // 3D fix
(int32_t)(_vehicleLatitude * 1E7),
(int32_t)(_vehicleLongitude * 1E7),
(int32_t)(_vehicleAltitude * 1000),
UINT16_MAX, UINT16_MAX, // HDOP/VDOP not known
UINT16_MAX, // velocity not known
UINT16_MAX, // course over ground not known
8); // satellite count
respondWithMavlinkMessage(msg);
}
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
void MockLink::_sendStatusTextMessages(void)
{
struct StatusMessage {
MAV_SEVERITY severity;
const char* msg;
};
static const struct StatusMessage rgMessages[] = {
{ MAV_SEVERITY_INFO, "#Testing audio output" },
{ MAV_SEVERITY_EMERGENCY, "Status text emergency" },
{ MAV_SEVERITY_ALERT, "Status text alert" },
{ MAV_SEVERITY_CRITICAL, "Status text critical" },
{ MAV_SEVERITY_ERROR, "Status text error" },
{ MAV_SEVERITY_WARNING, "Status text warning" },
{ MAV_SEVERITY_NOTICE, "Status text notice" },
{ MAV_SEVERITY_INFO, "Status text info" },
{ MAV_SEVERITY_DEBUG, "Status text debug" },
};
for (size_t i=0; i<sizeof(rgMessages)/sizeof(rgMessages[0]); i++) {
mavlink_message_t msg;
const struct StatusMessage* status = &rgMessages[i];
mavlink_msg_statustext_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
status->severity,
status->msg);
respondWithMavlinkMessage(msg);
}
}
MockConfiguration::MockConfiguration(const QString& name)
: LinkConfiguration(name)
, _firmwareType(MAV_AUTOPILOT_PX4)
{
}
MockConfiguration::MockConfiguration(MockConfiguration* source)
: LinkConfiguration(source)
{
_firmwareType = source->_firmwareType;
_sendStatusText = source->_sendStatusText;
}
void MockConfiguration::copyFrom(LinkConfiguration *source)
{
LinkConfiguration::copyFrom(source);
MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
if (!usource) {
qWarning() << "dynamic_cast failed" << source << usource;
return;
}
_firmwareType = usource->_firmwareType;
_sendStatusText = usource->_sendStatusText;
}
void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
settings.beginGroup(root);
settings.setValue(_firmwareTypeKey, (int)_firmwareType);
settings.setValue(_vehicleTypeKey, (int)_vehicleType);
settings.setValue(_sendStatusTextKey, _sendStatusText);
settings.sync();
settings.endGroup();
}
void MockConfiguration::loadSettings(QSettings& settings, const QString& root)
{
settings.beginGroup(root);
_firmwareType = (MAV_AUTOPILOT)settings.value(_firmwareTypeKey, (int)MAV_AUTOPILOT_PX4).toInt();
_vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
_sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
settings.endGroup();
}
void MockConfiguration::updateSettings()
{
if (_link) {
MockLink* ulink = dynamic_cast<MockLink*>(_link);
if (ulink) {
// Restart connect not supported
qWarning() << "updateSettings not supported";