Commit 2fd39fe1 authored by Don Gagne's avatar Don Gagne

parent a980fac9
...@@ -102,7 +102,7 @@ void APMSensorsComponentController::_startLogCalibration(void) ...@@ -102,7 +102,7 @@ void APMSensorsComponentController::_startLogCalibration(void)
{ {
_hideAllCalAreas(); _hideAllCalAreas();
connect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage); connect(_vehicle, &Vehicle::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage);
emit setAllCalButtonsEnabled(false); emit setAllCalButtonsEnabled(false);
if (_calTypeInProgress == CalTypeAccel || _calTypeInProgress == CalTypeCompassMot) { if (_calTypeInProgress == CalTypeAccel || _calTypeInProgress == CalTypeCompassMot) {
...@@ -152,7 +152,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll ...@@ -152,7 +152,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll
{ {
_vehicle->setConnectionLostEnabled(true); _vehicle->setConnectionLostEnabled(true);
disconnect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage); disconnect(_vehicle, &Vehicle::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage);
emit setAllCalButtonsEnabled(true); emit setAllCalButtonsEnabled(true);
_nextButton->setEnabled(false); _nextButton->setEnabled(false);
......
...@@ -26,26 +26,26 @@ PowerComponentController::PowerComponentController(void) ...@@ -26,26 +26,26 @@ PowerComponentController::PowerComponentController(void)
void PowerComponentController::calibrateEsc(void) void PowerComponentController::calibrateEsc(void)
{ {
_warningMessages.clear(); _warningMessages.clear();
connect(_uas, &UASInterface::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage); connect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
_uas->startCalibration(UASInterface::StartCalibrationEsc); _uas->startCalibration(UASInterface::StartCalibrationEsc);
} }
void PowerComponentController::busConfigureActuators(void) void PowerComponentController::busConfigureActuators(void)
{ {
_warningMessages.clear(); _warningMessages.clear();
connect(_uas, &UASInterface::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage); connect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
_uas->startBusConfig(UASInterface::StartBusConfigActuators); _uas->startBusConfig(UASInterface::StartBusConfigActuators);
} }
void PowerComponentController::stopBusConfigureActuators(void) void PowerComponentController::stopBusConfigureActuators(void)
{ {
disconnect(_uas, &UASInterface::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage); disconnect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
_uas->startBusConfig(UASInterface::EndBusConfigActuators); _uas->startBusConfig(UASInterface::EndBusConfigActuators);
} }
void PowerComponentController::_stopCalibration(void) void PowerComponentController::_stopCalibration(void)
{ {
disconnect(_uas, &UASInterface::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage); disconnect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
} }
void PowerComponentController::_stopBusConfig(void) void PowerComponentController::_stopBusConfig(void)
......
...@@ -89,7 +89,7 @@ void SensorsComponentController::_startLogCalibration(void) ...@@ -89,7 +89,7 @@ void SensorsComponentController::_startLogCalibration(void)
_unknownFirmwareVersion = false; _unknownFirmwareVersion = false;
_hideAllCalAreas(); _hideAllCalAreas();
connect(_uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage); connect(_vehicle, &Vehicle::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
_cancelButton->setEnabled(false); _cancelButton->setEnabled(false);
} }
...@@ -137,7 +137,7 @@ void SensorsComponentController::_resetInternalState(void) ...@@ -137,7 +137,7 @@ void SensorsComponentController::_resetInternalState(void)
void SensorsComponentController::_stopCalibration(SensorsComponentController::StopCalibrationCode code) void SensorsComponentController::_stopCalibration(SensorsComponentController::StopCalibrationCode code)
{ {
disconnect(_uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage); disconnect(_vehicle, &Vehicle::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
_compassButton->setEnabled(true); _compassButton->setEnabled(true);
_gyroButton->setEnabled(true); _gyroButton->setEnabled(true);
......
...@@ -434,17 +434,6 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess ...@@ -434,17 +434,6 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess
} }
} }
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 (instanceData->noisyPrearmMap.contains(messageText) && instanceData->noisyPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) {
return false;
}
instanceData->noisyPrearmMap[messageText] = QTime::currentTime();
vehicle->setPrearmError(messageText);
}
return true; return true;
} }
......
...@@ -145,7 +145,6 @@ public: ...@@ -145,7 +145,6 @@ public:
APMFirmwarePluginInstanceData(QObject* parent = NULL); APMFirmwarePluginInstanceData(QObject* parent = NULL);
bool textSeverityAdjustmentNeeded; bool textSeverityAdjustmentNeeded;
QMap<QString, QTime> noisyPrearmMap;
}; };
#endif #endif
...@@ -674,8 +674,8 @@ QObject* QGCApplication::_rootQmlObject() ...@@ -674,8 +674,8 @@ QObject* QGCApplication::_rootQmlObject()
void QGCApplication::showMessage(const QString& message) 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. // PreArm messages are handled by Vehicle and shown in Map
if (message.contains("PreArm:")) { if (message.startsWith(QStringLiteral("PreArm")) || message.startsWith(QStringLiteral("PREFLIGHT"))) {
return; return;
} }
......
...@@ -756,6 +756,10 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes ...@@ -756,6 +756,10 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_ESTIMATOR_STATUS: case MAVLINK_MSG_ID_ESTIMATOR_STATUS:
_handleEstimatorStatus(message); _handleEstimatorStatus(message);
break; break;
case MAVLINK_MSG_ID_STATUSTEXT:
_handleStatusText(message);
break;
case MAVLINK_MSG_ID_PING: case MAVLINK_MSG_ID_PING:
_handlePing(link, message); _handlePing(link, message);
break; break;
...@@ -813,6 +817,39 @@ void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message) ...@@ -813,6 +817,39 @@ void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message)
} }
} }
void Vehicle::_handleStatusText(mavlink_message_t& message)
{
QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
mavlink_msg_statustext_get_text(&message, b.data());
b[b.length()-1] = '\0';
QString messageText = QString(b);
bool skipSpoken = false;
if (messageText.startsWith(QStringLiteral("PreArm")) || messageText.startsWith(QStringLiteral("PREFLIGHT"))) {
// Limit repeated PreArm message to once every 10 seconds
if (_noisySpokenPrearmMap.contains(messageText) && _noisySpokenPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) {
skipSpoken = true;
} else {
_noisySpokenPrearmMap[messageText] = QTime::currentTime();
setPrearmError(messageText);
}
}
// If the message is NOTIFY or higher severity, or starts with a '#',
// then read it aloud.
int severity = mavlink_msg_statustext_get_severity(&message);
if (messageText.startsWith("#") || severity <= MAV_SEVERITY_NOTICE) {
messageText.remove("#");
if (!skipSpoken) {
qgcApp()->toolbox()->audioOutput()->say(messageText);
}
}
emit textMessageReceived(id(), message.compid, severity, messageText);
}
void Vehicle::_handleVfrHud(mavlink_message_t& message) void Vehicle::_handleVfrHud(mavlink_message_t& message)
{ {
mavlink_vfr_hud_t vfrHud; mavlink_vfr_hud_t vfrHud;
......
...@@ -1093,6 +1093,7 @@ signals: ...@@ -1093,6 +1093,7 @@ signals:
void priorityLinkNameChanged(const QString& priorityLinkName); void priorityLinkNameChanged(const QString& priorityLinkName);
void linksChanged(void); void linksChanged(void);
void linksPropertiesChanged(void); void linksPropertiesChanged(void);
void textMessageReceived(int uasid, int componentid, int severity, QString text);
void messagesReceivedChanged (); void messagesReceivedChanged ();
void messagesSentChanged (); void messagesSentChanged ();
...@@ -1233,6 +1234,7 @@ private: ...@@ -1233,6 +1234,7 @@ private:
void _handleAttitudeTarget(mavlink_message_t& message); void _handleAttitudeTarget(mavlink_message_t& message);
void _handleDistanceSensor(mavlink_message_t& message); void _handleDistanceSensor(mavlink_message_t& message);
void _handleEstimatorStatus(mavlink_message_t& message); void _handleEstimatorStatus(mavlink_message_t& message);
void _handleStatusText(mavlink_message_t& message);
// ArduPilot dialect messages // ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT) #if !defined(NO_ARDUPILOT_DIALECT)
void _handleCameraFeedback(const mavlink_message_t& message); void _handleCameraFeedback(const mavlink_message_t& message);
...@@ -1433,6 +1435,8 @@ private: ...@@ -1433,6 +1435,8 @@ private:
uint64_t _mavlinkLossCount = 0; uint64_t _mavlinkLossCount = 0;
float _mavlinkLossPercent = 0.0f; float _mavlinkLossPercent = 0.0f;
QMap<QString, QTime> _noisySpokenPrearmMap; ///< Used to prevent PreArm messages from being spoken too often
// FactGroup facts // FactGroup facts
Fact _rollFact; Fact _rollFact;
......
...@@ -308,32 +308,6 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -308,32 +308,6 @@ void UAS::receiveMessage(mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
mavlink_msg_statustext_get_text(&message, b.data());
// Ensure NUL-termination
b[b.length()-1] = '\0';
QString text = QString(b);
int severity = mavlink_msg_statustext_get_severity(&message);
// If the message is NOTIFY or higher severity, or starts with a '#',
// then read it aloud.
if (text.startsWith("#") || severity <= MAV_SEVERITY_NOTICE)
{
text.remove("#");
emit textMessageReceived(uasId, message.compid, severity, text);
_say(text.toLower(), severity);
}
else
{
emit textMessageReceived(uasId, message.compid, severity, text);
}
}
break;
case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE: case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
{ {
mavlink_data_transmission_handshake_t p; mavlink_data_transmission_handshake_t p;
...@@ -1613,12 +1587,6 @@ void UAS::unsetRCToParameterMap() ...@@ -1613,12 +1587,6 @@ void UAS::unsetRCToParameterMap()
} }
} }
void UAS::_say(const QString& text, int severity)
{
Q_UNUSED(severity);
qgcApp()->toolbox()->audioOutput()->say(text);
}
void UAS::shutdownVehicle(void) void UAS::shutdownVehicle(void)
{ {
#ifndef __mobile__ #ifndef __mobile__
......
...@@ -322,9 +322,6 @@ protected: ...@@ -322,9 +322,6 @@ protected:
quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent
quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent
private:
void _say(const QString& text, int severity = 6);
private: private:
Vehicle* _vehicle; Vehicle* _vehicle;
FirmwarePluginManager* _firmwarePluginManager; FirmwarePluginManager* _firmwarePluginManager;
......
...@@ -111,9 +111,6 @@ public slots: ...@@ -111,9 +111,6 @@ public slots:
virtual void unsetRCToParameterMap() = 0; virtual void unsetRCToParameterMap() = 0;
signals: signals:
/** @brief A text message from the system has been received */
void textMessageReceived(int uasid, int componentid, int severity, QString text);
/** /**
* @brief Update the error count of a device * @brief Update the error count of a device
* *
......
...@@ -17,7 +17,7 @@ ...@@ -17,7 +17,7 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "UASMessageHandler.h" #include "UASMessageHandler.h"
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "UAS.h" #include "Vehicle.h"
UASMessage::UASMessage(int componentid, int severity, QString text) UASMessage::UASMessage(int componentid, int severity, QString text)
{ {
...@@ -88,7 +88,7 @@ void UASMessageHandler::_activeVehicleChanged(Vehicle* vehicle) ...@@ -88,7 +88,7 @@ void UASMessageHandler::_activeVehicleChanged(Vehicle* vehicle)
{ {
// If we were already attached to an autopilot, disconnect it. // If we were already attached to an autopilot, disconnect it.
if (_activeVehicle) { if (_activeVehicle) {
disconnect(_activeVehicle->uas(), &UASInterface::textMessageReceived, this, &UASMessageHandler::handleTextMessage); disconnect(_activeVehicle, &Vehicle::textMessageReceived, this, &UASMessageHandler::handleTextMessage);
_activeVehicle = NULL; _activeVehicle = NULL;
clearMessages(); clearMessages();
emit textMessageReceived(NULL); emit textMessageReceived(NULL);
...@@ -99,7 +99,7 @@ void UASMessageHandler::_activeVehicleChanged(Vehicle* vehicle) ...@@ -99,7 +99,7 @@ void UASMessageHandler::_activeVehicleChanged(Vehicle* vehicle)
// Connect to the new UAS. // Connect to the new UAS.
clearMessages(); clearMessages();
_activeVehicle = vehicle; _activeVehicle = vehicle;
connect(_activeVehicle->uas(), &UASInterface::textMessageReceived, this, &UASMessageHandler::handleTextMessage); connect(_activeVehicle, &Vehicle::textMessageReceived, this, &UASMessageHandler::handleTextMessage);
} }
} }
......
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