Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
9be76b3a
Unverified
Commit
9be76b3a
authored
Sep 29, 2018
by
Don Gagne
Committed by
GitHub
Sep 29, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6898 from DonLakeFlyer/PreArmMessaging
Move ArduPilot preflight check handling to generic QGC
parents
1cc2ef6a
6163ce95
Changes
13
Hide whitespace changes
Inline
Side-by-side
Showing
13 changed files
with
76 additions
and
69 deletions
+76
-69
APMSensorsComponentController.cc
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
+2
-2
PowerComponentController.cc
src/AutoPilotPlugins/PX4/PowerComponentController.cc
+4
-4
SensorsComponentController.cc
src/AutoPilotPlugins/PX4/SensorsComponentController.cc
+2
-2
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+0
-11
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+0
-1
FlightDisplayViewWidgets.qml
src/FlightDisplay/FlightDisplayViewWidgets.qml
+20
-6
QGCApplication.cc
src/QGCApplication.cc
+2
-2
Vehicle.cc
src/Vehicle/Vehicle.cc
+39
-0
Vehicle.h
src/Vehicle/Vehicle.h
+4
-0
UAS.cc
src/uas/UAS.cc
+0
-32
UAS.h
src/uas/UAS.h
+0
-3
UASInterface.h
src/uas/UASInterface.h
+0
-3
UASMessageHandler.cc
src/uas/UASMessageHandler.cc
+3
-3
No files found.
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
View file @
9be76b3a
...
@@ -102,7 +102,7 @@ void APMSensorsComponentController::_startLogCalibration(void)
...
@@ -102,7 +102,7 @@ void APMSensorsComponentController::_startLogCalibration(void)
{
{
_hideAllCalAreas
();
_hideAllCalAreas
();
connect
(
_
uas
,
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
APMSensorsComponentController
::
_handleUASTextMessage
);
connect
(
_
vehicle
,
&
Vehicl
e
::
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
,
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
APMSensorsComponentController
::
_handleUASTextMessage
);
disconnect
(
_
vehicle
,
&
Vehicl
e
::
textMessageReceived
,
this
,
&
APMSensorsComponentController
::
_handleUASTextMessage
);
emit
setAllCalButtonsEnabled
(
true
);
emit
setAllCalButtonsEnabled
(
true
);
_nextButton
->
setEnabled
(
false
);
_nextButton
->
setEnabled
(
false
);
...
...
src/AutoPilotPlugins/PX4/PowerComponentController.cc
View file @
9be76b3a
...
@@ -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
,
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
PowerComponentController
::
_handleUASTextMessage
);
connect
(
_
vehicle
,
&
Vehicl
e
::
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
,
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
PowerComponentController
::
_handleUASTextMessage
);
connect
(
_
vehicle
,
&
Vehicl
e
::
textMessageReceived
,
this
,
&
PowerComponentController
::
_handleUASTextMessage
);
_uas
->
startBusConfig
(
UASInterface
::
StartBusConfigActuators
);
_uas
->
startBusConfig
(
UASInterface
::
StartBusConfigActuators
);
}
}
void
PowerComponentController
::
stopBusConfigureActuators
(
void
)
void
PowerComponentController
::
stopBusConfigureActuators
(
void
)
{
{
disconnect
(
_
uas
,
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
PowerComponentController
::
_handleUASTextMessage
);
disconnect
(
_
vehicle
,
&
Vehicl
e
::
textMessageReceived
,
this
,
&
PowerComponentController
::
_handleUASTextMessage
);
_uas
->
startBusConfig
(
UASInterface
::
EndBusConfigActuators
);
_uas
->
startBusConfig
(
UASInterface
::
EndBusConfigActuators
);
}
}
void
PowerComponentController
::
_stopCalibration
(
void
)
void
PowerComponentController
::
_stopCalibration
(
void
)
{
{
disconnect
(
_
uas
,
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
PowerComponentController
::
_handleUASTextMessage
);
disconnect
(
_
vehicle
,
&
Vehicl
e
::
textMessageReceived
,
this
,
&
PowerComponentController
::
_handleUASTextMessage
);
}
}
void
PowerComponentController
::
_stopBusConfig
(
void
)
void
PowerComponentController
::
_stopBusConfig
(
void
)
...
...
src/AutoPilotPlugins/PX4/SensorsComponentController.cc
View file @
9be76b3a
...
@@ -89,7 +89,7 @@ void SensorsComponentController::_startLogCalibration(void)
...
@@ -89,7 +89,7 @@ void SensorsComponentController::_startLogCalibration(void)
_unknownFirmwareVersion
=
false
;
_unknownFirmwareVersion
=
false
;
_hideAllCalAreas
();
_hideAllCalAreas
();
connect
(
_
uas
,
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
SensorsComponentController
::
_handleUASTextMessage
);
connect
(
_
vehicle
,
&
Vehicl
e
::
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
,
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
SensorsComponentController
::
_handleUASTextMessage
);
disconnect
(
_
vehicle
,
&
Vehicl
e
::
textMessageReceived
,
this
,
&
SensorsComponentController
::
_handleUASTextMessage
);
_compassButton
->
setEnabled
(
true
);
_compassButton
->
setEnabled
(
true
);
_gyroButton
->
setEnabled
(
true
);
_gyroButton
->
setEnabled
(
true
);
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
9be76b3a
...
@@ -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
;
}
}
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
9be76b3a
...
@@ -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
src/FlightDisplay/FlightDisplayViewWidgets.qml
View file @
9be76b3a
...
@@ -104,37 +104,51 @@ Item {
...
@@ -104,37 +104,51 @@ Item {
}
}
//-- Map warnings
//-- Map warnings
Rectangle
{
anchors.margins
:
-
ScreenTools
.
defaultFontPixelHeight
anchors.fill
:
warningsCol
color
:
"
white
"
opacity
:
0.5
radius
:
ScreenTools
.
defaultFontPixelWidth
/
2
visible
:
warningsCol
.
noGPSLockVisible
||
warningsCol
.
prearmErrorVisible
}
Column
{
Column
{
id
:
warningsCol
anchors.horizontalCenter
:
parent
.
horizontalCenter
anchors.horizontalCenter
:
parent
.
horizontalCenter
anchors.top
:
parent
.
verticalCenter
anchors.top
:
parent
.
verticalCenter
spacing
:
ScreenTools
.
defaultFontPixelHeight
spacing
:
ScreenTools
.
defaultFontPixelHeight
property
bool
noGPSLockVisible
:
_activeVehicle
&&
!
_activeVehicle
.
coordinate
.
isValid
&&
_mainIsMap
property
bool
prearmErrorVisible
:
_activeVehicle
&&
_activeVehicle
.
prearmError
QGCLabel
{
QGCLabel
{
anchors.horizontalCenter
:
parent
.
horizontalCenter
anchors.horizontalCenter
:
parent
.
horizontalCenter
visible
:
_activeVehicle
&&
!
_activeVehicle
.
coordinate
.
isValid
&&
_mainIsMap
visible
:
warningsCol
.
noGPSLockVisible
z
:
QGroundControl
.
zOrderTopMost
z
:
QGroundControl
.
zOrderTopMost
color
:
mapPal
.
text
color
:
"
black
"
font.pointSize
:
ScreenTools
.
largeFontPointSize
font.pointSize
:
ScreenTools
.
largeFontPointSize
text
:
qsTr
(
"
No GPS Lock for Vehicle
"
)
text
:
qsTr
(
"
No GPS Lock for Vehicle
"
)
}
}
QGCLabel
{
QGCLabel
{
anchors.horizontalCenter
:
parent
.
horizontalCenter
anchors.horizontalCenter
:
parent
.
horizontalCenter
visible
:
_activeVehicle
&&
_activeVehicle
.
prearmError
visible
:
warningsCol
.
prearmErrorVisible
z
:
QGroundControl
.
zOrderTopMost
z
:
QGroundControl
.
zOrderTopMost
color
:
mapPal
.
text
color
:
"
black
"
font.pointSize
:
ScreenTools
.
largeFontPointSize
font.pointSize
:
ScreenTools
.
largeFontPointSize
text
:
_activeVehicle
?
_activeVehicle
.
prearmError
:
""
text
:
_activeVehicle
?
_activeVehicle
.
prearmError
:
""
}
}
QGCLabel
{
QGCLabel
{
anchors.horizontalCenter
:
parent
.
horizontalCenter
anchors.horizontalCenter
:
parent
.
horizontalCenter
visible
:
_activeVehicle
&&
_activeVehicle
.
prearmError
visible
:
warningsCol
.
prearmErrorVisible
width
:
ScreenTools
.
defaultFontPixelWidth
*
50
width
:
ScreenTools
.
defaultFontPixelWidth
*
50
horizontalAlignment
:
Text
.
AlignHCenter
horizontalAlignment
:
Text
.
AlignHCenter
wrapMode
:
Text
.
WordWrap
wrapMode
:
Text
.
WordWrap
z
:
QGroundControl
.
zOrderTopMost
z
:
QGroundControl
.
zOrderTopMost
color
:
mapPal
.
text
color
:
"
black
"
font.pointSize
:
ScreenTools
.
largeFontPointSize
font.pointSize
:
ScreenTools
.
largeFontPointSize
text
:
"
The vehicle has failed a pre-arm check. In order to arm the vehicle, resolve the failure.
"
text
:
"
The vehicle has failed a pre-arm check. In order to arm the vehicle, resolve the failure.
"
}
}
...
...
src/QGCApplication.cc
View file @
9be76b3a
...
@@ -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"
),
Qt
::
CaseInsensitive
))
{
return
;
return
;
}
}
...
...
src/Vehicle/Vehicle.cc
View file @
9be76b3a
...
@@ -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,41 @@ void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message)
...
@@ -813,6 +817,41 @@ 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
);
int
severity
=
mavlink_msg_statustext_get_severity
(
&
message
);
bool
skipSpoken
=
false
;
bool
ardupilotPrearm
=
messageText
.
startsWith
(
QStringLiteral
(
"PreArm"
));
bool
px4Prearm
=
messageText
.
startsWith
(
QStringLiteral
(
"preflight"
),
Qt
::
CaseInsensitive
)
&&
severity
>=
MAV_SEVERITY_CRITICAL
;
if
(
ardupilotPrearm
||
px4Prearm
)
{
// 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.
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
;
...
...
src/Vehicle/Vehicle.h
View file @
9be76b3a
...
@@ -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
.
0
f
;
float
_mavlinkLossPercent
=
0
.
0
f
;
QMap
<
QString
,
QTime
>
_noisySpokenPrearmMap
;
///< Used to prevent PreArm messages from being spoken too often
// FactGroup facts
// FactGroup facts
Fact
_rollFact
;
Fact
_rollFact
;
...
...
src/uas/UAS.cc
View file @
9be76b3a
...
@@ -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__
...
...
src/uas/UAS.h
View file @
9be76b3a
...
@@ -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
;
...
...
src/uas/UASInterface.h
View file @
9be76b3a
...
@@ -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
*
*
...
...
src/uas/UASMessageHandler.cc
View file @
9be76b3a
...
@@ -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
(),
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
UASMessageHandler
::
handleTextMessage
);
disconnect
(
_activeVehicle
,
&
Vehicl
e
::
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
(),
&
UASInterfac
e
::
textMessageReceived
,
this
,
&
UASMessageHandler
::
handleTextMessage
);
connect
(
_activeVehicle
,
&
Vehicl
e
::
textMessageReceived
,
this
,
&
UASMessageHandler
::
handleTextMessage
);
}
}
}
}
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment