Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Cleanup MockLink Helper Classes #12345

Merged
merged 1 commit into from
Jan 18, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/Comms/MockLink/MockConfiguration.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ void MockConfiguration::copyFrom(const LinkConfiguration *source)
Q_ASSERT(source);
LinkConfiguration::copyFrom(source);

const MockConfiguration* const mockLinkSource = qobject_cast<const MockConfiguration*>(source);
const MockConfiguration *const mockLinkSource = qobject_cast<const MockConfiguration*>(source);
Q_ASSERT(mockLinkSource);

setFirmwareType(mockLinkSource->firmwareType());
Expand Down
3 changes: 2 additions & 1 deletion src/Comms/MockLink/MockConfiguration.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,10 @@
#pragma once

#include "LinkConfiguration.h"
#include "MAVLinkLib.h"

#include <QtCore/QLoggingCategory>
#include "MAVLinkLib.h"


Q_DECLARE_LOGGING_CATEGORY(MockConfigurationLog)

Expand Down
150 changes: 75 additions & 75 deletions src/Comms/MockLink/MockLink.cc

Large diffs are not rendered by default.

141 changes: 66 additions & 75 deletions src/Comms/MockLink/MockLink.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
#include "LinkInterface.h"
#include "MAVLinkLib.h"
#include "MockConfiguration.h"
#include "MockLinkFTP.h"
#include "MockLinkMissionItemHandler.h"

#include <QtCore/QElapsedTimer>
Expand All @@ -22,6 +21,8 @@
#include <QtCore/QMutex>
#include <QtPositioning/QGeoCoordinate>

class MockLinkFTP;

Q_DECLARE_LOGGING_CATEGORY(MockLinkLog)
Q_DECLARE_LOGGING_CATEGORY(MockLinkVerboseLog)

Expand All @@ -36,31 +37,18 @@ class MockLink : public LinkInterface
bool isConnected() const final { return _connected; }
void disconnect() final;

Q_INVOKABLE void setCommLost(bool commLost) { _commLost = commLost; }
Q_INVOKABLE void simulateConnectionRemoved();

int vehicleId() const { return _vehicleSystemId; }
MAV_AUTOPILOT getFirmwareType() const { return _firmwareType; }
void setFirmwareType(MAV_AUTOPILOT autopilot) { _firmwareType = autopilot; }
void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; }
void setFailureMode(MockConfiguration::FailureMode_t failureMode) { _failureMode = failureMode; }

/// APM stack has strange handling of the first item of the mission list. If it has no
/// onboard mission items, sometimes it sends back a home position in position 0 and
/// sometimes it doesn't. Don't ask. This option allows you to configure that behavior
/// for unit testing.
void setAPMMissionResponseMode(bool sendHomePositionOnEmptyList) { _apmSendHomePositionOnEmptyList = sendHomePositionOnEmptyList; }

void emitRemoteControlChannelRawChanged(int channel, uint16_t raw);

/// Sends the specified mavlink message to QGC
void respondWithMavlinkMessage(const mavlink_message_t &msg);

MockLinkFTP *mockLinkFTP() const { return _mockLinkFTP; }

struct ADSBVehicle {
QGeoCoordinate coordinate;
double angle;
double altitude; // Store unique altitude for each vehicle
};
std::vector<ADSBVehicle> _adsbVehicles; // Store data for multiple ADS-B vehicles
MockLinkFTP *mockLinkFTP() const;

/// Sets a failure mode for unit testingqgcm
/// @param failureMode Type of failure to simulate
Expand All @@ -84,8 +72,16 @@ class MockLink : public LinkInterface
/// Returns the filename for the simulated log file. Only available after a download is requested.
QString logDownloadFile() const { return _logDownloadFilename; }

Q_INVOKABLE void setCommLost(bool commLost) { _commLost = commLost; }
Q_INVOKABLE void simulateConnectionRemoved();
void clearReceivedMavCommandCounts() { _receivedMavCommandCountMap.clear(); }
int receivedMavCommandCount(MAV_CMD command) const { return _receivedMavCommandCountMap[command]; }

enum RequestMessageFailureMode_t {
FailRequestMessageNone,
FailRequestMessageCommandAcceptedMsgNotSent,
FailRequestMessageCommandUnsupported,
FailRequestMessageCommandNoResponse,
};
void setRequestMessageFailureMode(RequestMessageFailureMode_t failureMode) { _requestMessageFailureMode = failureMode; }

static MockLink *startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
static MockLink *startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
Expand All @@ -106,23 +102,12 @@ class MockLink : public LinkInterface
static constexpr MAV_CMD MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_FAILED = static_cast<MAV_CMD>(MAV_CMD_USER_5 + 3);
static constexpr MAV_CMD MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK = static_cast<MAV_CMD>(MAV_CMD_USER_5 + 4);

void clearReceivedMavCommandCounts() { _receivedMavCommandCountMap.clear(); }
int receivedMavCommandCount(MAV_CMD command) const { return _receivedMavCommandCountMap[command]; }

enum RequestMessageFailureMode_t {
FailRequestMessageNone,
FailRequestMessageCommandAcceptedMsgNotSent,
FailRequestMessageCommandUnsupported,
FailRequestMessageCommandNoResponse,
};
void setRequestMessageFailureMode(RequestMessageFailureMode_t failureMode) { _requestMessageFailureMode = failureMode; }

signals:
void writeBytesQueuedSignal(const QByteArray &bytes);
void highLatencyTransmissionEnabledChanged(bool highLatencyTransmissionEnabled);

private slots:
/// @brief Called when QGC wants to write bytes to the MAV
/// Called when QGC wants to write bytes to the MAV
void _writeBytes(const QByteArray &bytes) final;

void _writeBytesQueued(const QByteArray &bytes);
Expand All @@ -138,17 +123,20 @@ private slots:

void run() final;

uint8_t mavlinkAuxChannel() const { return _mavlinkAuxChannel; }
bool mavlinkAuxChannelIsSet() const;
uint8_t _getMavlinkAuxChannel() const { return _mavlinkAuxChannel; }
bool _mavlinkAuxChannelIsSet() const;

void _sendHeartBeat();
void _sendHighLatency2();
/// @brief Handle incoming bytes which are meant to be interpreted by the NuttX shell
void _loadParams();

/// Convert from a parameter variant to the float value from mavlink_param_union_t
float _floatUnionForParam(int componentId, const QString &paramName);
void _setParamFloatUnionIntoMap(int componentId, const QString &paramName, float paramFloat);

/// Handle incoming bytes which are meant to be interpreted by the NuttX shell
void _handleIncomingNSHBytes(const char *bytes, int cBytes);
/// @brief Handle incoming bytes which are meant to be handled by the mavlink protocol
/// Handle incoming bytes which are meant to be handled by the mavlink protocol
void _handleIncomingMavlinkBytes(const uint8_t *bytes, int cBytes);
void _handleIncomingMavlinkMsg(const mavlink_message_t &msg);
void _loadParams();
void _handleHeartBeat(const mavlink_message_t &msg);
void _handleSetMode(const mavlink_message_t &msg);
void _handleParamRequestList(const mavlink_message_t &msg);
Expand All @@ -164,9 +152,9 @@ private slots:
void _handleLogRequestData(const mavlink_message_t &msg);
void _handleParamMapRC(const mavlink_message_t &msg);
bool _handleRequestMessage(const mavlink_command_long_t &request, bool &noAck);
/// Convert from a parameter variant to the float value from mavlink_param_union_t
float _floatUnionForParam(int componentId, const QString &paramName);
void _setParamFloatUnionIntoMap(int componentId, const QString &paramName, float paramFloat);

void _sendHeartBeat();
void _sendHighLatency2();
void _sendHomePosition();
void _sendGpsRawInt();
void _sendGlobalPositionInt();
Expand All @@ -178,33 +166,42 @@ private slots:
void _respondWithAutopilotVersion();
void _sendRCChannels();
/// Sends the next parameter to the vehicle
void _paramRequestListWorker();
void _logDownloadWorker();
void _sendADSBVehicles();
void _moveADSBVehicle(int vehicleIndex);
void _sendGeneralMetaData();
void _sendRemoteIDArmStatus();

void _paramRequestListWorker();
void _logDownloadWorker();
void _moveADSBVehicle(int vehicleIndex);

static MockLink *_startMockLinkWorker(const QString &configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode);
static MockLink *_startMockLink(MockConfiguration *mockConfig);

/// Creates a file with random contents of the specified size.
/// @return Fully qualified path to created file
static QString _createRandomFile(uint32_t byteCount);

MockLinkMissionItemHandler *_missionItemHandler = nullptr;
const MockConfiguration *_mockConfig = nullptr;
const MAV_AUTOPILOT _firmwareType = MAV_AUTOPILOT_PX4;
const MAV_TYPE _vehicleType = MAV_TYPE_QUADROTOR;
const bool _sendStatusText = false;
const MockConfiguration::FailureMode_t _failureMode = MockConfiguration::FailNone;
const uint8_t _vehicleSystemId = 0;
const double _vehicleLatitude = 0.0;
const double _vehicleLongitude = 0.0;
// These are just set for reporting the fields in _respondWithAutopilotVersion()
// and ensuring that the Vehicle reports the fields in Vehicle::firmwareBoardVendorId etc.
// They do not control any mock simulation (and it is up to the Custom build to do that).
const uint16_t _boardVendorId = 0;
const uint16_t _boardProductId = 0;
MockLinkMissionItemHandler *const _missionItemHandler = nullptr;
MockLinkFTP *const _mockLinkFTP = nullptr;

uint8_t _mavlinkAuxChannel = std::numeric_limits<uint8_t>::max();
QMutex _mavlinkAuxMutex;

QString _name = QString("MockLink");
bool _connected = false;

uint8_t _vehicleSystemId = 0;
uint8_t _vehicleComponentId = MAV_COMP_ID_AUTOPILOT1;

bool _inNSH = false;
bool _mavlinkStarted = true;

uint8_t _mavBaseMode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint32_t _mavCustomMode = PX4CustomMode::MANUAL;
Expand All @@ -219,49 +216,36 @@ private slots:
int32_t _battery2TimeRemaining = _batteryMaxTimeRemaining;
MAV_BATTERY_CHARGE_STATE _battery2ChargeState = MAV_BATTERY_CHARGE_STATE_OK;

MAV_AUTOPILOT _firmwareType = MAV_AUTOPILOT_PX4;
MAV_TYPE _vehicleType = MAV_TYPE_QUADROTOR;
double _vehicleLatitude = 0.0;
double _vehicleLongitude = 0.0;
double _vehicleAltitudeAMSL = _defaultVehicleHomeAltitude;
bool _commLost = false;
bool _highLatencyTransmissionEnabled = true;

// These are just set for reporting the fields in _respondWithAutopilotVersion()
// and ensuring that the Vehicle reports the fields in Vehicle::firmwareBoardVendorId etc.
// They do not control any mock simulation (and it is up to the Custom build to do that).
uint16_t _boardVendorId = 0;
uint16_t _boardProductId = 0;

MockLinkFTP *_mockLinkFTP = nullptr;

bool _sendStatusText = false;
bool _apmSendHomePositionOnEmptyList = false;
MockConfiguration::FailureMode_t _failureMode = MockConfiguration::FailNone;

int _sendHomePositionDelayCount = 10; ///< No home position for 4 seconds
int _sendGPSPositionDelayCount = 100; ///< No gps lock for 5 seconds

int _currentParamRequestListComponentIndex = -1; ///< Current component index for param request list workflow, -1 for no request in progress
int _currentParamRequestListParamIndex = -1; ///< Current parameter index for param request list workflow

static constexpr uint16_t _logDownloadLogId = 0; ///< Id of siumulated log file
static constexpr uint32_t _logDownloadFileSize = 1000; ///< Size of simulated log file

QString _logDownloadFilename; ///< Filename for log download which is in progress
uint32_t _logDownloadCurrentOffset = 0; ///< Current offset we are sending from
uint32_t _logDownloadBytesRemaining = 0; ///< Number of bytes still to send, 0 = send inactive

QList<QGeoCoordinate> _adsbVehicleCoordinates; ///< List for multiple vehicles
static constexpr int _numberOfVehicles = 5; ///< Number of ADS-B vehicles
double _adsbAngles[_numberOfVehicles]{}; ///< Array for angles of each vehicle

RequestMessageFailureMode_t _requestMessageFailureMode = FailRequestMessageNone;

QMap<MAV_CMD, int> _receivedMavCommandCountMap;
QMap<int, QMap<QString, QVariant>> _mapParamName2Value;
QMap<int, QMap<QString, MAV_PARAM_TYPE>> _mapParamName2MavParamType;

struct ADSBVehicle {
QGeoCoordinate coordinate;
double angle = 0.0;
double altitude = 0.0; ///< Store unique altitude for each vehicle
};
QList<ADSBVehicle> _adsbVehicles; ///< Store data for multiple ADS-B vehicles
QList<QGeoCoordinate> _adsbVehicleCoordinates; ///< List for multiple vehicles
static constexpr int _numberOfVehicles = 5; ///< Number of ADS-B vehicles
double _adsbAngles[_numberOfVehicles]{}; ///< Array for angles of each vehicle

static int _nextVehicleSystemId;

// Vehicle position is set close to default Gazebo vehicle location. This allows for multi-vehicle
Expand All @@ -271,5 +255,12 @@ private slots:
static constexpr double _defaultVehicleHomeAltitude = 488.056;

static constexpr const char *_failParam = "COM_FLTMODE6";

static constexpr uint8_t _vehicleComponentId = MAV_COMP_ID_AUTOPILOT1;

static constexpr uint16_t _logDownloadLogId = 0; ///< Id of siumulated log file
static constexpr uint32_t _logDownloadFileSize = 1000; ///< Size of simulated log file

static constexpr bool _mavlinkStarted = true;
};

Loading
Loading