Commit 513d1583 authored by Jacob Walser's avatar Jacob Walser

Handle firmware-specific facts in firmwareplugin

parent a656877e
......@@ -83,7 +83,7 @@ public:
bool isGuidedMode (const Vehicle* vehicle) const final;
void pauseVehicle (Vehicle* vehicle);
int manualControlReservedButtonCount(void);
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) final;
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override;
void adjustOutgoingMavlinkMessage (Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message) final;
void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final;
......
......@@ -99,6 +99,8 @@ ArduSubFirmwarePlugin::ArduSubFirmwarePlugin(void)
_remapParamNameIntialized = true;
}
fwFactGroup = new APMSubmarineFactGroup(this);
}
int ArduSubFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const
......@@ -155,3 +157,59 @@ const QVariantList& ArduSubFirmwarePlugin::toolBarIndicators(const Vehicle* vehi
}
return _toolBarIndicators;
}
void ArduSubFirmwarePlugin::_handleNamedValueFloat(mavlink_message_t* message)
{
mavlink_named_value_float_t value;
mavlink_msg_named_value_float_decode(message, &value);
QString name = QString(value.name);
if (name == "CamTilt") {
fwFactGroup->getFact("camera tilt")->setRawValue(value.value * 100);
} else if (name == "TetherTrn") {
fwFactGroup->getFact("tether turns")->setRawValue(value.value);
} else if (name == "Lights1") {
fwFactGroup->getFact("lights 1")->setRawValue(value.value * 100);
} else if (name == "Lights2") {
fwFactGroup->getFact("lights 2")->setRawValue(value.value * 100);
}
}
void ArduSubFirmwarePlugin::_handleMavlinkMessage(mavlink_message_t* message)
{
switch (message->msgid) {
case (MAVLINK_MSG_ID_NAMED_VALUE_FLOAT):
_handleNamedValueFloat(message);
}
}
bool ArduSubFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
_handleMavlinkMessage(message);
return APMFirmwarePlugin::adjustIncomingMavlinkMessage(vehicle, message);
}
const char* APMSubmarineFactGroup::_camTiltFactName = "camera tilt";
const char* APMSubmarineFactGroup::_tetherTurnsFactName = "tether turns";
const char* APMSubmarineFactGroup::_lightsLevel1FactName = "lights 1";
const char* APMSubmarineFactGroup::_lightsLevel2FactName = "lights 2";
APMSubmarineFactGroup::APMSubmarineFactGroup(QObject* parent)
: FactGroup(300, ":/json/Vehicle/SubmarineFact.json", parent)
, _camTiltFact (0, _camTiltFactName, FactMetaData::valueTypeDouble)
, _tetherTurnsFact (0, _tetherTurnsFactName, FactMetaData::valueTypeDouble)
, _lightsLevel1Fact (0, _lightsLevel1FactName, FactMetaData::valueTypeDouble)
, _lightsLevel2Fact (0, _lightsLevel2FactName, FactMetaData::valueTypeDouble)
{
_addFact(&_camTiltFact, _camTiltFactName);
_addFact(&_tetherTurnsFact, _tetherTurnsFactName);
_addFact(&_lightsLevel1Fact, _lightsLevel1FactName);
_addFact(&_lightsLevel2Fact, _lightsLevel2FactName);
// Start out as not available "--.--"
_camTiltFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_tetherTurnsFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_lightsLevel1Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_lightsLevel2Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
}
......@@ -88,11 +88,45 @@ public:
const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final;
const QVariantList& toolBarIndicators(const Vehicle* vehicle) final;
bool adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
private:
QVariantList _toolBarIndicators;
static bool _remapParamNameIntialized;
static FirmwarePlugin::remapParamNameMajorVersionMap_t _remapParamName;
void _handleNamedValueFloat(mavlink_message_t* message);
void _handleMavlinkMessage(mavlink_message_t* message);
};
class APMSubmarineFactGroup : public FactGroup
{
Q_OBJECT
public:
APMSubmarineFactGroup(QObject* parent = NULL);
Q_PROPERTY(Fact* camTilt READ camTilt CONSTANT)
Q_PROPERTY(Fact* tetherTurns READ tetherTurns CONSTANT)
Q_PROPERTY(Fact* lightsLevel1 READ lightsLevel1 CONSTANT)
Q_PROPERTY(Fact* lightsLevel2 READ lightsLevel2 CONSTANT)
Fact* camTilt (void) { return &_camTiltFact; }
Fact* tetherTurns (void) { return &_tetherTurnsFact; }
Fact* lightsLevel1 (void) { return &_lightsLevel1Fact; }
Fact* lightsLevel2 (void) { return &_lightsLevel2Fact; }
static const char* _camTiltFactName;
static const char* _tetherTurnsFactName;
static const char* _lightsLevel1FactName;
static const char* _lightsLevel2FactName;
static const char* _settingsGroup;
private:
Fact _camTiltFact;
Fact _tetherTurnsFact;
Fact _lightsLevel1Fact;
Fact _lightsLevel2Fact;
};
#endif
......@@ -295,6 +295,9 @@ public:
// FIXME: Hack workaround for non pluginize FollowMe support
static const char* px4FollowMeFlightMode;
/// Used to add additional firmware-specific facts to the vehicle values widget
FactGroup* fwFactGroup = NULL;
protected:
// Arms the vehicle with validation and retries
// @return: true - vehicle armed, false - vehicle failed to arm
......@@ -307,7 +310,6 @@ protected:
private:
QVariantList _toolBarIndicatorList;
static QVariantList _cameraList; ///< Standard QGC camera list
};
class FirmwarePluginFactory : public QObject
......
......@@ -59,7 +59,6 @@ const char* Vehicle::_batteryFactGroupName = "battery";
const char* Vehicle::_windFactGroupName = "wind";
const char* Vehicle::_vibrationFactGroupName = "vibration";
const char* Vehicle::_temperatureFactGroupName = "temperature";
const char* Vehicle::_submarineFactGroupName = "sub";
Vehicle::Vehicle(LinkInterface* link,
int vehicleId,
......@@ -373,9 +372,9 @@ void Vehicle::_commonInit(void)
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName);
if (_vehicleType == MAV_TYPE_SUBMARINE) {
_submarineFactGroup = new VehicleSubmarineFactGroup(this);
_addFactGroup(_submarineFactGroup, _submarineFactGroupName);
// Add firmware-specific fact group, if provided
if (_firmwarePlugin->fwFactGroup) {
_addFactGroup(_firmwarePlugin->fwFactGroup, "FWPlugin");
}
_flightDistanceFact.setRawValue(0);
......@@ -603,10 +602,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_WIND:
_handleWind(message);
break;
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
_handleNamedValueFloat(message);
break;
}
emit mavlinkMessageReceived(message);
......@@ -1174,27 +1169,6 @@ void Vehicle::_handleScaledPressure3(mavlink_message_t& message) {
_temperatureFactGroup.temperature3()->setRawValue(pressure.temperature / 100.0);
}
void Vehicle::_handleNamedValueFloat(mavlink_message_t &message) {
if (!_submarineFactGroup) {
return;
}
mavlink_named_value_float_t value;
mavlink_msg_named_value_float_decode(&message, &value);
QString name = QString(value.name);
if (name == "CamTilt") {
_submarineFactGroup->camTilt()->setRawValue(value.value * 100);
} else if (name == "TetherTrn") {
_submarineFactGroup->tetherTurns()->setRawValue(value.value);
} else if (name == "Lights1") {
_submarineFactGroup->lightsLevel1()->setRawValue(value.value * 100);
} else if (name == "Lights2") {
_submarineFactGroup->lightsLevel2()->setRawValue(value.value * 100);
}
}
bool Vehicle::_containsLink(LinkInterface* link)
{
return _links.contains(link);
......@@ -2743,27 +2717,3 @@ VehicleTemperatureFactGroup::VehicleTemperatureFactGroup(QObject* parent)
_temperature2Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_temperature3Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
}
const char* VehicleSubmarineFactGroup::_camTiltFactName = "camera tilt";
const char* VehicleSubmarineFactGroup::_tetherTurnsFactName = "tether turns";
const char* VehicleSubmarineFactGroup::_lightsLevel1FactName = "lights 1";
const char* VehicleSubmarineFactGroup::_lightsLevel2FactName = "lights 2";
VehicleSubmarineFactGroup::VehicleSubmarineFactGroup(QObject* parent)
: FactGroup(300, ":/json/Vehicle/SubmarineFact.json", parent)
, _camTiltFact (0, _camTiltFactName, FactMetaData::valueTypeDouble)
, _tetherTurnsFact (0, _tetherTurnsFactName, FactMetaData::valueTypeDouble)
, _lightsLevel1Fact (0, _lightsLevel1FactName, FactMetaData::valueTypeDouble)
, _lightsLevel2Fact (0, _lightsLevel2FactName, FactMetaData::valueTypeDouble)
{
_addFact(&_camTiltFact, _camTiltFactName);
_addFact(&_tetherTurnsFact, _tetherTurnsFactName);
_addFact(&_lightsLevel1Fact, _lightsLevel1FactName);
_addFact(&_lightsLevel2Fact, _lightsLevel2FactName);
// Start out as not available "--.--"
_camTiltFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_tetherTurnsFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_lightsLevel1Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_lightsLevel2Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
}
......@@ -214,37 +214,6 @@ private:
Fact _temperature3Fact;
};
class VehicleSubmarineFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleSubmarineFactGroup(QObject* parent = NULL);
Q_PROPERTY(Fact* camTilt READ camTilt CONSTANT)
Q_PROPERTY(Fact* tetherTurns READ tetherTurns CONSTANT)
Q_PROPERTY(Fact* lightsLevel1 READ lightsLevel1 CONSTANT)
Q_PROPERTY(Fact* lightsLevel2 READ lightsLevel2 CONSTANT)
Fact* camTilt (void) { return &_camTiltFact; }
Fact* tetherTurns (void) { return &_tetherTurnsFact; }
Fact* lightsLevel1 (void) { return &_lightsLevel1Fact; }
Fact* lightsLevel2 (void) { return &_lightsLevel2Fact; }
static const char* _camTiltFactName;
static const char* _tetherTurnsFactName;
static const char* _lightsLevel1FactName;
static const char* _lightsLevel2FactName;
static const char* _settingsGroup;
private:
Fact _camTiltFact;
Fact _tetherTurnsFact;
Fact _lightsLevel1Fact;
Fact _lightsLevel2Fact;
};
class Vehicle : public FactGroup
{
Q_OBJECT
......@@ -381,7 +350,6 @@ public:
Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
Q_PROPERTY(FactGroup* submarineFactGroup READ submarineFactGroup CONSTANT)
Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged)
......@@ -644,7 +612,6 @@ public:
FactGroup* windFactGroup (void) { return &_windFactGroup; }
FactGroup* vibrationFactGroup (void) { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
FactGroup* submarineFactGroup (void) { return _submarineFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled);
......@@ -865,7 +832,6 @@ private:
void _handleScaledPressure(mavlink_message_t& message);
void _handleScaledPressure2(mavlink_message_t& message);
void _handleScaledPressure3(mavlink_message_t& message);
void _handleNamedValueFloat(mavlink_message_t& message);
void _handleCameraFeedback(const mavlink_message_t& message);
void _handleCameraImageCaptured(const mavlink_message_t& message);
void _missionManagerError(int errorCode, const QString& errorMsg);
......@@ -1053,7 +1019,6 @@ private:
VehicleWindFactGroup _windFactGroup;
VehicleVibrationFactGroup _vibrationFactGroup;
VehicleTemperatureFactGroup _temperatureFactGroup;
VehicleSubmarineFactGroup* _submarineFactGroup;
static const char* _rollFactName;
static const char* _pitchFactName;
......@@ -1071,7 +1036,6 @@ private:
static const char* _windFactGroupName;
static const char* _vibrationFactGroupName;
static const char* _temperatureFactGroupName;
static const char* _submarineFactGroupName;
static const int _vehicleUIUpdateRateMSecs = 100;
......
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