Commit 7c3c6162 authored by Don Gagne's avatar Don Gagne

APM PreArm message handling

parent 0d3b4721
......@@ -391,13 +391,15 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
_soloVideoHandshake(vehicle);
}
// ArduPilot PreArm messages can come across very frequently especially on Solo, which seems to send them once a second.
// Filter them out if they come too quickly.
if (messageText.startsWith("PreArm")) {
// ArduPilot PreArm messages can come across very frequently especially on Solo, which seems to send them once a second.
// Filter them out if they come too quickly.
if (_noisyPrearmMap.contains(messageText) && _noisyPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) {
return false;
}
_noisyPrearmMap[messageText] = QTime::currentTime();
vehicle->setPrearmError(messageText);
}
return true;
......
......@@ -61,24 +61,28 @@ Item {
id: _dropButtonsExclusiveGroup
}
//-- Vehicle GPS lock display
//-- Map warnings
Column {
id: gpsLockColumn
y: (parent.height - height) / 2
width: parent.width
Repeater {
model: QGroundControl.multiVehicleManager.vehicles
delegate:
QGCLabel {
width: gpsLockColumn.width
horizontalAlignment: Text.AlignHCenter
visible: !object.coordinateValid
text: "No GPS Lock for Vehicle #" + object.id
z: QGroundControl.zOrderMapItems - 2
color: mapPal.text
}
anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
visible: _activeVehicle && !_activeVehicle.coordinateValid
z: QGroundControl.zOrderTopMost
color: mapPal.text
font.pixelSize: ScreenTools.largeFontPixelSize
text: "No GPS Lock for Vehicle"
}
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
visible: _activeVehicle && !_activeVehicle.coordinateValid
z: QGroundControl.zOrderTopMost
color: mapPal.text
font.pixelSize: ScreenTools.largeFontPixelSize
text: _activeVehicle ? _activeVehicle.prearmError : ""
}
}
......
......@@ -723,6 +723,11 @@ QObject* QGCApplication::_rootQmlObject(void)
void QGCApplication::showMessage(const QString& message)
{
// Special case hack for ArduPilot prearm messages. These show up in the center of the map, so no need for popup.
if (message.contains("PreArm:")) {
return;
}
QObject* rootQmlObject = _rootQmlObject();
if (rootQmlObject) {
......
......@@ -168,6 +168,11 @@ Vehicle::Vehicle(LinkInterface* link,
_refreshTimer->setInterval(UPDATE_TIMER);
_refreshTimer->start(UPDATE_TIMER);
// PreArm Error self-destruct timer
connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
_prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
_prearmErrorTimer.setSingleShot(true);
// Connection Lost time
_connectionLostTimer.setInterval(Vehicle::_connectionLostTimeoutMSecs);
_connectionLostTimer.setSingleShot(false);
......@@ -1526,6 +1531,19 @@ void Vehicle::doCommandLong(int component, MAV_CMD command, float param1, float
sendMessage(msg);
}
void Vehicle::setPrearmError(const QString& prearmError)
{
_prearmError = prearmError;
emit prearmErrorChanged(_prearmError);
if (!_prearmError.isEmpty()) {
_prearmErrorTimer.start();
}
}
void Vehicle::_prearmErrorTimeout(void)
{
setPrearmError(QString());
}
const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
......
......@@ -286,6 +286,7 @@ public:
Q_PROPERTY(bool fixedWing READ fixedWing CONSTANT)
Q_PROPERTY(bool multiRotor READ multiRotor CONSTANT)
Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged)
/// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY(bool flying READ flying WRITE setFlying NOTIFY flyingChanged)
......@@ -443,6 +444,9 @@ public:
void setFlying(bool flying);
void setGuidedMode(bool guidedMode);
QString prearmError(void) const { return _prearmError; }
void setPrearmError(const QString& prearmError);
QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
int flowImageIndex() { return _flowImageIndex; }
......@@ -533,6 +537,7 @@ signals:
void autoDisconnectChanged(bool autoDisconnectChanged);
void flyingChanged(bool flying);
void guidedModeChanged(bool guidedMode);
void prearmErrorChanged(const QString& prearmError);
void messagesReceivedChanged ();
void messagesSentChanged ();
......@@ -594,6 +599,7 @@ private slots:
/** @brief A new camera image has arrived */
void _imageReady (UASInterface* uas);
void _connectionLostTimeout(void);
void _prearmErrorTimeout(void);
private:
bool _containsLink(LinkInterface* link);
......@@ -662,6 +668,10 @@ private:
bool _autoDisconnect; ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
bool _flying;
QString _prearmError;
QTimer _prearmErrorTimer;
static const int _prearmErrorTimeoutMSecs = 35 * 1000; ///< Take away prearm error after 35 seconds
// Lost connection handling
bool _connectionLost;
bool _connectionLostEnabled;
......
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