Commit a067300d authored by Don Gagne's avatar Don Gagne

Warn on unsupported APM version

parent 7f43851e
......@@ -28,6 +28,7 @@
#include "Generic/GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack
#include "QGCMAVLink.h"
#include "QGCApplication.h"
QGC_LOGGING_CATEGORY(APMFirmwarePluginLog, "APMFirmwarePluginLog")
......@@ -211,7 +212,7 @@ int APMFirmwarePlugin::manualControlReservedButtonCount(void)
return -1;
}
void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
void APMFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
if (message->msgid == MAVLINK_MSG_ID_PARAM_VALUE) {
mavlink_param_value_t paramValue;
......@@ -296,9 +297,6 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
mavlink_statustext_t statusText;
mavlink_msg_statustext_decode(message, &statusText);
// APM user facing calibration messages come through as high severity, we need to parse them out
// and lower the severity on them so that they don't pop in the users face.
if (!_firmwareVersion.isValid() || statusText.severity < MAV_SEVERITY_NOTICE) {
QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
......@@ -314,9 +312,42 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
// found version string
_firmwareVersion = APMFirmwareVersion(messageText);
_textSeverityAdjustmentNeeded = _isTextSeverityAdjustmentNeeded(_firmwareVersion);
if (!_firmwareVersion.isBeta() && !_firmwareVersion.isDev()) {
int supportedMajorNumber = -1;
int supportedMinorNumber = -1;
switch (vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING:
supportedMajorNumber = 3;
supportedMinorNumber = 4;
break;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER:
case MAV_TYPE_SUBMARINE:
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
supportedMajorNumber = 3;
supportedMinorNumber = 3;
break;
default:
break;
}
if (supportedMajorNumber != -1) {
if (_firmwareVersion.majorNumber() < supportedMajorNumber || _firmwareVersion.minorNumber() < supportedMinorNumber) {
qgcApp()->showMessage(QString("QGroundControl fully supports Version %1.%2 and above. You are using a version prior to that. This combination is untested, you may run into unpredictable results.").arg(supportedMajorNumber).arg(supportedMinorNumber));
}
}
}
}
}
// APM user facing calibration messages come through as high severity, we need to parse them out
// and lower the severity on them so that they don't pop in the users face.
if (messageText.contains("Place vehicle") || messageText.contains("Calibration successful")) {
_adjustCalibrationMessageSeverity(message);
return;
......
......@@ -86,7 +86,7 @@ public:
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
......
......@@ -90,8 +90,9 @@ public:
/// Called before any mavlink message is processed by Vehicle such taht the firmwre plugin
/// can adjust any message characteristics. This is handy to adjust or differences in mavlink
/// spec implementations such that the base code can remain mavlink generic.
/// @param vehicle Vehicle message came from
/// @param message[in,out] Mavlink message to adjust if needed.
virtual void adjustMavlinkMessage(mavlink_message_t* message) = 0;
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) = 0;
/// Called when Vehicle is first created to send any necessary mavlink messages to the firmware.
virtual void initializeVehicle(Vehicle* vehicle) = 0;
......
......@@ -90,8 +90,9 @@ int GenericFirmwarePlugin::manualControlReservedButtonCount(void)
return -1;
}
void GenericFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
Q_UNUSED(vehicle);
Q_UNUSED(message);
// Generic plugin does no message adjustment
......
......@@ -42,7 +42,7 @@ public:
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
......
......@@ -177,8 +177,9 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void)
return 0; // 0 buttons reserved for rc switch simulation
}
void PX4FirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
void PX4FirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
Q_UNUSED(vehicle);
Q_UNUSED(message);
// PX4 Flight Stack plugin does no message adjustment
......
......@@ -42,7 +42,7 @@ public:
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
......
......@@ -221,7 +221,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
}
// Give the plugin a change to adjust the message contents
_firmwarePlugin->adjustMavlinkMessage(&message);
_firmwarePlugin->adjustMavlinkMessage(this, &message);
switch (message.msgid) {
case MAVLINK_MSG_ID_HOME_POSITION:
......@@ -442,7 +442,7 @@ void Vehicle::_sendMessage(mavlink_message_t message)
MAVLinkProtocol* mavlink = _mavlink;
// Give the plugin a chance to adjust
_firmwarePlugin->adjustMavlinkMessage(&message);
_firmwarePlugin->adjustMavlinkMessage(this, &message);
static const uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
......
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