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
36abc43f
Commit
36abc43f
authored
May 24, 2016
by
Beat Küng
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
gps: use GPS_RTCM_DATA mavlink message for RTCM, use fragmentation if needed
parent
3a71177d
Changes
2
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
30 additions
and
11 deletions
+30
-11
RTCMMavlink.cc
src/GPS/RTCM/RTCMMavlink.cc
+27
-11
RTCMMavlink.h
src/GPS/RTCM/RTCMMavlink.h
+3
-0
No files found.
src/GPS/RTCM/RTCMMavlink.cc
View file @
36abc43f
...
@@ -11,7 +11,6 @@
...
@@ -11,7 +11,6 @@
#include "RTCMMavlink.h"
#include "RTCMMavlink.h"
#include "MultiVehicleManager.h"
#include "MultiVehicleManager.h"
#include "MAVLinkProtocol.h"
#include "Vehicle.h"
#include "Vehicle.h"
#include <cstdio>
#include <cstdio>
...
@@ -24,8 +23,6 @@ RTCMMavlink::RTCMMavlink(QGCToolbox& toolbox)
...
@@ -24,8 +23,6 @@ RTCMMavlink::RTCMMavlink(QGCToolbox& toolbox)
void
RTCMMavlink
::
RTCMDataUpdate
(
QByteArray
message
)
void
RTCMMavlink
::
RTCMDataUpdate
(
QByteArray
message
)
{
{
Q_ASSERT
(
message
.
size
()
<=
110
);
//mavlink message uses a fixed-size buffer
/* statistics */
/* statistics */
_bandwidthByteCounter
+=
message
.
size
();
_bandwidthByteCounter
+=
message
.
size
();
qint64
elapsed
=
_bandwidthTimer
.
elapsed
();
qint64
elapsed
=
_bandwidthTimer
.
elapsed
();
...
@@ -34,19 +31,38 @@ void RTCMMavlink::RTCMDataUpdate(QByteArray message)
...
@@ -34,19 +31,38 @@ void RTCMMavlink::RTCMDataUpdate(QByteArray message)
_bandwidthTimer
.
restart
();
_bandwidthTimer
.
restart
();
_bandwidthByteCounter
=
0
;
_bandwidthByteCounter
=
0
;
}
}
QmlObjectListModel
&
vehicles
=
*
_toolbox
.
multiVehicleManager
()
->
vehicles
();
MAVLinkProtocol
*
mavlinkProtocol
=
_toolbox
.
mavlinkProtocol
();
mavlink_gps_inject_data_t
mavlinkRtcmData
;
memset
(
&
mavlinkRtcmData
,
0
,
sizeof
(
mavlink_gps_inject_data_t
));
const
int
maxMessageLength
=
MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN
;
mavlink_gps_rtcm_data_t
mavlinkRtcmData
;
memset
(
&
mavlinkRtcmData
,
0
,
sizeof
(
mavlink_gps_rtcm_data_t
));
if
(
message
.
size
()
<
maxMessageLength
)
{
mavlinkRtcmData
.
len
=
message
.
size
();
mavlinkRtcmData
.
len
=
message
.
size
();
memcpy
(
&
mavlinkRtcmData
.
data
,
message
.
data
(),
message
.
size
());
memcpy
(
&
mavlinkRtcmData
.
data
,
message
.
data
(),
message
.
size
());
sendMessageToVehicle
(
mavlinkRtcmData
);
}
else
{
//we need to fragment
int
start
=
0
;
while
(
start
<
message
.
size
())
{
int
length
=
std
::
min
(
message
.
size
()
-
start
,
maxMessageLength
);
mavlinkRtcmData
.
flags
=
1
;
//fragmented
mavlinkRtcmData
.
len
=
length
;
memcpy
(
&
mavlinkRtcmData
.
data
,
message
.
data
()
+
start
,
length
);
sendMessageToVehicle
(
mavlinkRtcmData
);
start
+=
length
;
}
}
}
void
RTCMMavlink
::
sendMessageToVehicle
(
const
mavlink_gps_rtcm_data_t
&
msg
)
{
QmlObjectListModel
&
vehicles
=
*
_toolbox
.
multiVehicleManager
()
->
vehicles
();
MAVLinkProtocol
*
mavlinkProtocol
=
_toolbox
.
mavlinkProtocol
();
for
(
int
i
=
0
;
i
<
vehicles
.
count
();
i
++
)
{
for
(
int
i
=
0
;
i
<
vehicles
.
count
();
i
++
)
{
Vehicle
*
vehicle
=
qobject_cast
<
Vehicle
*>
(
vehicles
[
i
]);
Vehicle
*
vehicle
=
qobject_cast
<
Vehicle
*>
(
vehicles
[
i
]);
mavlink_message_t
message
;
mavlink_message_t
message
;
mavlink_msg_gps_
inject
_data_encode
(
mavlinkProtocol
->
getSystemId
(),
mavlink_msg_gps_
rtcm
_data_encode
(
mavlinkProtocol
->
getSystemId
(),
mavlinkProtocol
->
getComponentId
(),
&
message
,
&
m
avlinkRtcmData
);
mavlinkProtocol
->
getComponentId
(),
&
message
,
&
m
sg
);
vehicle
->
sendMessage
(
message
);
vehicle
->
sendMessage
(
message
);
}
}
}
}
src/GPS/RTCM/RTCMMavlink.h
View file @
36abc43f
...
@@ -14,6 +14,7 @@
...
@@ -14,6 +14,7 @@
#include <QElapsedTimer>
#include <QElapsedTimer>
#include "QGCToolbox.h"
#include "QGCToolbox.h"
#include "MAVLinkProtocol.h"
/**
/**
** class RTCMMavlink
** class RTCMMavlink
...
@@ -30,6 +31,8 @@ public slots:
...
@@ -30,6 +31,8 @@ public slots:
void
RTCMDataUpdate
(
QByteArray
message
);
void
RTCMDataUpdate
(
QByteArray
message
);
private:
private:
void
sendMessageToVehicle
(
const
mavlink_gps_rtcm_data_t
&
msg
);
QGCToolbox
&
_toolbox
;
QGCToolbox
&
_toolbox
;
QElapsedTimer
_bandwidthTimer
;
QElapsedTimer
_bandwidthTimer
;
int
_bandwidthByteCounter
=
0
;
int
_bandwidthByteCounter
=
0
;
...
...
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