Commit 012de5a5 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into Airmap

# Conflicts:
#	src/Vehicle/Vehicle.cc
parents a1f8de63 15f188a0
......@@ -138,7 +138,7 @@ void
AirMapFlightPlanManager::setFlightStartTime(QDateTime start)
{
if(start < QDateTime::currentDateTime()) {
start = QDateTime::currentDateTime().addSecs(60);
start = QDateTime::currentDateTime().addSecs(1);
}
if(_flightStartTime != start) {
_flightStartTime = start;
......@@ -478,14 +478,8 @@ AirMapFlightPlanManager::_updateRulesAndFeatures(std::vector<RuleSet::Id>& rules
void
AirMapFlightPlanManager::_updateFlightStartEndTime(DateTime& start_time, DateTime& end_time)
{
if(_flightStartsNow) {
setFlightStartTime(QDateTime::currentDateTime().addSecs(60));
} else {
if(_flightStartTime < QDateTime::currentDateTime()) {
//-- Can't start in the past
_flightStartTime = QDateTime::currentDateTime();
emit flightStartTimeChanged();
}
if(_flightStartsNow || _flightStartTime < QDateTime::currentDateTime()) {
setFlightStartTime(QDateTime::currentDateTime().addSecs(1));
}
quint64 startt = static_cast<quint64>(_flightStartTime.toUTC().toMSecsSinceEpoch());
start_time = airmap::from_milliseconds_since_epoch(airmap::milliseconds(static_cast<qint64>(startt)));
......
......@@ -208,7 +208,8 @@ Vehicle::Vehicle(LinkInterface* link,
_mavlink = _toolbox->mavlinkProtocol();
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(_mavlink, &MAVLinkProtocol::mavlinkMessageStatus, this, &Vehicle::_mavlinkMessageStatus);
_addLink(link);
......@@ -1845,7 +1846,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand)
// This routine specifically does not clear _priorityLink when there are no links remaining.
// By doing this we hold a reference on the last link as the Vehicle shuts down. Thus preventing shutdown
// ordering NULL pointer crashes where priorityLink() is still called during shutdown sequence.
// ordering nullptr pointer crashes where priorityLink() is still called during shutdown sequence.
if (_links.count() == 0) {
return;
}
......@@ -3652,6 +3653,17 @@ void Vehicle::_adsbTimerTimeout()
}
}
void Vehicle::_mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent)
{
if(uasId == _id) {
_mavlinkSentCount = totalSent;
_mavlinkReceivedCount = totalReceived;
_mavlinkLossCount = totalLoss;
_mavlinkLossPercent = lossPercent;
emit mavlinkStatusChanged();
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
......
......@@ -625,6 +625,10 @@ public:
Q_PROPERTY(QString priorityLinkName READ priorityLinkName WRITE setPriorityLinkByName NOTIFY priorityLinkNameChanged)
Q_PROPERTY(QVariantList links READ links NOTIFY linksChanged)
Q_PROPERTY(LinkInterface* priorityLink READ priorityLink NOTIFY priorityLinkNameChanged)
Q_PROPERTY(quint64 mavlinkSentCount READ mavlinkSentCount NOTIFY mavlinkStatusChanged)
Q_PROPERTY(quint64 mavlinkReceivedCount READ mavlinkReceivedCount NOTIFY mavlinkStatusChanged)
Q_PROPERTY(quint64 mavlinkLossCount READ mavlinkLossCount NOTIFY mavlinkStatusChanged)
Q_PROPERTY(float mavlinkLossPercent READ mavlinkLossPercent NOTIFY mavlinkStatusChanged)
// Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
......@@ -1047,6 +1051,11 @@ public:
/// Vehicle is about to be deleted
void prepareDelete();
quint64 mavlinkSentCount () { return _mavlinkSentCount; } /// Calculated total number of messages sent to us
quint64 mavlinkReceivedCount () { return _mavlinkReceivedCount; } /// Total number of sucessful messages received
quint64 mavlinkLossCount () { return _mavlinkLossCount; } /// Total number of lost messages
float mavlinkLossPercent () { return _mavlinkLossPercent; } /// Running loss rate
signals:
void allLinksInactive(Vehicle* vehicle);
void coordinateChanged(QGeoCoordinate coordinate);
......@@ -1150,6 +1159,7 @@ signals:
// MAVLink protocol version
void requestProtocolVersion(unsigned version);
void mavlinkStatusChanged();
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
......@@ -1182,6 +1192,7 @@ private slots:
void _updateHobbsMeter(void);
void _vehicleParamLoaded(bool ready);
void _sendQGCTimeToVehicle(void);
void _mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
void _trafficUpdate (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
void _adsbTimerTimeout ();
......@@ -1417,6 +1428,11 @@ private:
SharedLinkInterfacePointer _priorityLink; // We always keep a reference to the priority link to manage shutdown ordering
bool _priorityLinkCommanded;
uint64_t _mavlinkSentCount = 0;
uint64_t _mavlinkReceivedCount = 0;
uint64_t _mavlinkLossCount = 0;
float _mavlinkLossPercent = 0.0f;
// FactGroup facts
Fact _rollFact;
......
This diff is collapsed.
......@@ -65,27 +65,6 @@ public:
unsigned getCurrentVersion() {
return _current_version;
}
/**
* Retrieve a total of all successfully parsed packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
qint32 getReceivedPacketCount(const LinkInterface *link) const {
return totalReceiveCounter[link->mavlinkChannel()];
}
/**
* Retrieve a total of all parsing errors for the specified link.
* @returns -1 if this is not available for this protocol, # of errors otherwise.
*/
qint32 getParsingErrorCount(const LinkInterface *link) const {
return totalErrorCounter[link->mavlinkChannel()];
}
/**
* Retrieve a total of all dropped packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
qint32 getDroppedPacketCount(const LinkInterface *link) const {
return totalLossCounter[link->mavlinkChannel()];
}
/**
* Reset the counters for all metadata for this link.
*/
......@@ -122,18 +101,20 @@ public slots:
void checkForLostLogFiles(void);
protected:
bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC
QMutex receiveMutex; ///< Mutex to protect receiveBytes function
int lastIndex[256][256]; ///< Store the last received sequence ID for each system/componenet pair
int totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< The total number of successfully received messages
int totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Total messages lost during transmission.
int totalErrorCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Total count of all parsing errors. Generally <= totalLossCounter.
int currReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Received messages during this sample time window. Used for calculating loss %.
int currLossCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Lost messages during this sample time window. Used for calculating loss %.
bool versionMismatchIgnore;
int systemId;
unsigned _current_version;
unsigned _radio_version_mismatch_count;
bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC
uint8_t lastIndex[256][256]; ///< Store the last received sequence ID for each system/componenet pair
uint8_t firstMessage[256][256]; ///< First message flag
uint64_t totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< The total number of successfully received messages
uint64_t totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Total messages lost during transmission.
float runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]; ///< Loss rate
mavlink_message_t _message = {};
mavlink_status_t _status = {};
bool versionMismatchIgnore;
int systemId;
unsigned _current_version;
unsigned _radio_version_mismatch_count;
signals:
/// Heartbeat received on link
......@@ -148,8 +129,7 @@ signals:
/** @brief Emitted if a new system ID was set */
void systemIdChanged(int systemId);
void receiveLossPercentChanged(int uasId, float lossPercent);
void receiveLossTotalChanged(int uasId, int totalLoss);
void mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
/**
* @brief Emitted if a new radio status packet received
......
......@@ -16,8 +16,7 @@
*
*/
#ifndef _PROTOCOLINTERFACE_H_
#define _PROTOCOLINTERFACE_H_
#pragma once
#include <QThread>
#include <QString>
......@@ -37,26 +36,8 @@ class ProtocolInterface : public QThread
{
Q_OBJECT
public:
virtual ~ProtocolInterface () {}
virtual QString getName() = 0;
/**
* Retrieve a total of all successfully parsed packets for the specified link.
* @param link The link to return metadata about.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
virtual qint32 getReceivedPacketCount(const LinkInterface *link) const = 0;
/**
* Retrieve a total of all parsing errors for the specified link.
* @param link The link to return metadata about.
* @returns -1 if this is not available for this protocol, # of errors otherwise.
*/
virtual qint32 getParsingErrorCount(const LinkInterface *link) const = 0;
/**
* Retrieve a total of all dropped packets for the specified link.
* @param link The link to return metadata about.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
virtual qint32 getDroppedPacketCount(const LinkInterface *link) const = 0;
virtual ~ProtocolInterface () {}
virtual QString getName () = 0;
/**
* Reset the received, error, and dropped counts for the given link. Useful for
* when reconnecting a link.
......@@ -65,13 +46,11 @@ public:
virtual void resetMetadataForLink(LinkInterface *link) = 0;
public slots:
virtual void receiveBytes(LinkInterface *link, QByteArray b) = 0;
virtual void linkStatusChanged(bool connected) = 0;
virtual void receiveBytes (LinkInterface *link, QByteArray b) = 0;
virtual void linkStatusChanged (bool connected) = 0;
signals:
/** @brief Update the packet loss from one system */
void receiveLossChanged(int uasId, float loss);
void receiveLossChanged (int uasId, float loss);
};
#endif // _PROTOCOLINTERFACE_H_
......@@ -30,6 +30,7 @@ Rectangle {
property int _selectedCount: 0
property real _columnSpacing: ScreenTools.defaultFontPixelHeight * 0.25
property bool _uploadedSelected: false
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
QGCPalette { id: qgcPal }
......@@ -152,6 +153,92 @@ Rectangle {
}
}
//-----------------------------------------------------------------
//-- Mavlink Status
Item {
width: __mavlinkRoot.width * 0.8
height: mavStatusLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
id: mavStatusLabel
text: qsTr("MAVLink Link Status (Current Vehicle)")
font.family: ScreenTools.demiboldFontFamily
}
}
Rectangle {
height: mavStatusColumn.height + (ScreenTools.defaultFontPixelHeight * 2)
width: __mavlinkRoot.width * 0.8
color: qgcPal.windowShade
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
Column {
id: mavStatusColumn
width: gcsColumn.width
spacing: _columnSpacing
anchors.centerIn: parent
//-----------------------------------------------------------------
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
width: _labelWidth
text: qsTr("Total messages sent (computed):")
anchors.verticalCenter: parent.verticalCenter
}
QGCLabel {
width: _valueWidth
text: _activeVehicle ? _activeVehicle.mavlinkSentCount : qsTr("Not Connected")
anchors.verticalCenter: parent.verticalCenter
}
}
//-----------------------------------------------------------------
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
width: _labelWidth
text: qsTr("Total messages received:")
anchors.verticalCenter: parent.verticalCenter
}
QGCLabel {
width: _valueWidth
text: _activeVehicle ? _activeVehicle.mavlinkReceivedCount : qsTr("Not Connected")
anchors.verticalCenter: parent.verticalCenter
}
}
//-----------------------------------------------------------------
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
width: _labelWidth
text: qsTr("Total message loss:")
anchors.verticalCenter: parent.verticalCenter
}
QGCLabel {
width: _valueWidth
text: _activeVehicle ? _activeVehicle.mavlinkLossCount : qsTr("Not Connected")
anchors.verticalCenter: parent.verticalCenter
}
}
//-----------------------------------------------------------------
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
width: _labelWidth
text: qsTr("Loss rate:")
anchors.verticalCenter: parent.verticalCenter
}
QGCLabel {
width: _valueWidth
text: _activeVehicle ? _activeVehicle.mavlinkLossPercent.toFixed(0) + '%' : qsTr("Not Connected")
anchors.verticalCenter: parent.verticalCenter
}
}
}
}
//-----------------------------------------------------------------
//-- Mavlink Logging
Item {
width: __mavlinkRoot.width * 0.8
......
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