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
6e9d785c
Commit
6e9d785c
authored
Mar 24, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Drop high rate PreArm messages
Also filter solo version string
parent
e03fb849
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
25 additions
and
10 deletions
+25
-10
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+22
-8
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+3
-2
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
6e9d785c
...
...
@@ -32,6 +32,7 @@
QGC_LOGGING_CATEGORY
(
APMFirmwarePluginLog
,
"APMFirmwarePluginLog"
)
static
const
QRegExp
APM_COPTER_REXP
(
"^(ArduCopter|APM:Copter)"
);
static
const
QRegExp
APM_SOLO_REXP
(
"^(APM:Copter solo-)"
);
static
const
QRegExp
APM_PLANE_REXP
(
"^(ArduPlane|APM:Plane)"
);
static
const
QRegExp
APM_ROVER_REXP
(
"^(ArduRover|APM:Rover)"
);
static
const
QRegExp
APM_PX4NUTTX_REXP
(
"^PX4: .*NuttX: .*"
);
...
...
@@ -43,6 +44,7 @@ static const QRegExp VERSION_REXP("^(APM:Copter|APM:Plane|APM:Rover|ArduCopter|A
// minimum firmware versions that don't suffer from mavlink severity inversion bug.
// https://github.com/diydrones/apm_planner/issues/788
static
const
QString
MIN_SOLO_VERSION_WITH_CORRECT_SEVERITY_MSGS
(
"APM:Copter solo-1.2.0"
);
static
const
QString
MIN_COPTER_VERSION_WITH_CORRECT_SEVERITY_MSGS
(
"APM:Copter V3.4.0"
);
static
const
QString
MIN_PLANE_VERSION_WITH_CORRECT_SEVERITY_MSGS
(
"APM:Plane V3.4.0"
);
static
const
QString
MIN_ROVER_VERSION_WITH_CORRECT_SEVERITY_MSGS
(
"APM:Rover V2.6.0"
);
...
...
@@ -300,7 +302,7 @@ void APMFirmwarePlugin::_handleParamSet(Vehicle* vehicle, mavlink_message_t* mes
mavlink_msg_param_set_encode
(
message
->
sysid
,
message
->
compid
,
message
,
&
paramSet
);
}
void
APMFirmwarePlugin
::
_handleStatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
bool
APMFirmwarePlugin
::
_handleStatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
{
QString
messageText
;
...
...
@@ -311,7 +313,7 @@ void APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
messageText
=
_getMessageText
(
message
);
qCDebug
(
APMFirmwarePluginLog
)
<<
messageText
;
if
(
!
_firmwareVersion
.
isValid
())
{
if
(
!
_firmwareVersion
.
isValid
()
&&
!
messageText
.
contains
(
APM_SOLO_REXP
)
)
{
// if don't know firmwareVersion yet, try and see if this message contains it
if
(
messageText
.
contains
(
APM_COPTER_REXP
)
||
messageText
.
contains
(
APM_PLANE_REXP
)
||
messageText
.
contains
(
APM_ROVER_REXP
))
{
// found version string
...
...
@@ -355,7 +357,7 @@ void APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
if
(
messageText
.
contains
(
"Place vehicle"
)
||
messageText
.
contains
(
"Calibration successful"
))
{
_adjustCalibrationMessageSeverity
(
message
);
return
;
return
true
;
}
}
...
...
@@ -370,10 +372,21 @@ void APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
// The following messages are incorrectly labeled as warning message.
// Fixed in newer firmware (unreleased at this point), but still in older firmware.
if
(
messageText
.
contains
(
APM_COPTER_REXP
)
||
messageText
.
contains
(
APM_PLANE_REXP
)
||
messageText
.
contains
(
APM_ROVER_REXP
)
||
if
(
messageText
.
contains
(
APM_COPTER_REXP
)
||
messageText
.
contains
(
APM_
SOLO_REXP
)
||
messageText
.
contains
(
APM_
PLANE_REXP
)
||
messageText
.
contains
(
APM_ROVER_REXP
)
||
messageText
.
contains
(
APM_PX4NUTTX_REXP
)
||
messageText
.
contains
(
APM_FRAME_REXP
)
||
messageText
.
contains
(
APM_SYSID_REXP
))
{
_setInfoSeverity
(
message
);
}
// 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"
))
{
if
(
_noisyPrearmMap
.
contains
(
messageText
)
&&
_noisyPrearmMap
[
messageText
].
msecsTo
(
QTime
::
currentTime
())
<
(
10
*
1000
))
{
return
false
;
}
_noisyPrearmMap
[
messageText
]
=
QTime
::
currentTime
();
}
return
true
;
}
void
APMFirmwarePlugin
::
_handleHeartbeat
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
...
...
@@ -396,11 +409,11 @@ void APMFirmwarePlugin::_handleHeartbeat(Vehicle* vehicle, mavlink_message_t* me
vehicle
->
setFlying
(
flying
);
}
void
APMFirmwarePlugin
::
adjustIncomingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
bool
APMFirmwarePlugin
::
adjustIncomingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
{
//-- Don't process messages to/from UDP Bridge. It doesn't suffer from these issues
if
(
message
->
compid
==
MAV_COMP_ID_UDP_BRIDGE
)
{
return
;
return
true
;
}
switch
(
message
->
msgid
)
{
...
...
@@ -408,12 +421,13 @@ void APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_m
_handleParamValue
(
vehicle
,
message
);
break
;
case
MAVLINK_MSG_ID_STATUSTEXT
:
_handleStatusText
(
vehicle
,
message
);
break
;
return
_handleStatusText
(
vehicle
,
message
);
case
MAVLINK_MSG_ID_HEARTBEAT
:
_handleHeartbeat
(
vehicle
,
message
);
break
;
}
return
true
;
}
void
APMFirmwarePlugin
::
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
6e9d785c
...
...
@@ -91,7 +91,7 @@ public:
bool
isGuidedMode
(
const
Vehicle
*
vehicle
)
const
final
;
void
pauseVehicle
(
Vehicle
*
vehicle
);
int
manualControlReservedButtonCount
(
void
)
final
;
void
adjustIncomingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
bool
adjustIncomingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
void
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
void
initializeVehicle
(
Vehicle
*
vehicle
)
final
;
bool
sendHomePositionToVehicle
(
void
)
final
;
...
...
@@ -116,12 +116,13 @@ private:
QString
_getMessageText
(
mavlink_message_t
*
message
)
const
;
void
_handleParamValue
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleParamSet
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleStatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
bool
_handleStatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleHeartbeat
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
APMFirmwareVersion
_firmwareVersion
;
bool
_textSeverityAdjustmentNeeded
;
QList
<
APMCustomMode
>
_supportedModes
;
QMap
<
QString
,
QTime
>
_noisyPrearmMap
;
};
#endif
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