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
f803ac47
Commit
f803ac47
authored
Mar 27, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #3091 from DonLakeFlyer/APMPreArmHandling
APM PreArm message handling
parents
0d3b4721
7c3c6162
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
58 additions
and
19 deletions
+58
-19
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+4
-2
FlightDisplayViewWidgets.qml
src/FlightDisplay/FlightDisplayViewWidgets.qml
+21
-17
QGCApplication.cc
src/QGCApplication.cc
+5
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+18
-0
Vehicle.h
src/Vehicle/Vehicle.h
+10
-0
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
f803ac47
...
...
@@ -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
;
...
...
src/FlightDisplay/FlightDisplayViewWidgets.qml
View file @
f803ac47
...
...
@@ -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
:
""
}
}
...
...
src/QGCApplication.cc
View file @
f803ac47
...
...
@@ -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
)
{
...
...
src/Vehicle/Vehicle.cc
View file @
f803ac47
...
...
@@ -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"
;
...
...
src/Vehicle/Vehicle.h
View file @
f803ac47
...
...
@@ -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
;
...
...
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