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
de4a1528
Commit
de4a1528
authored
Feb 17, 2020
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
a6d15868
Changes
4
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
109 additions
and
41 deletions
+109
-41
APMFollowComponent.FactMetaData.json
...AutoPilotPlugins/APM/APMFollowComponent.FactMetaData.json
+1
-1
APMFollowComponent.qml
src/AutoPilotPlugins/APM/APMFollowComponent.qml
+83
-33
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+7
-6
FollowMe.cc
src/FollowMe/FollowMe.cc
+18
-1
No files found.
src/AutoPilotPlugins/APM/APMFollowComponent.FactMetaData.json
View file @
de4a1528
...
...
@@ -20,7 +20,7 @@
},
{
"name"
:
"height"
,
"shortDescription"
:
"Vertical distance from
ground sta
tion to vehicle"
,
"shortDescription"
:
"Vertical distance from
Launch (home) posi
tion to vehicle"
,
"type"
:
"double"
,
"min"
:
0
,
"decimalPlaces"
:
1
,
...
...
src/AutoPilotPlugins/APM/APMFollowComponent.qml
View file @
de4a1528
This diff is collapsed.
Click to expand it.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
de4a1528
...
...
@@ -1136,15 +1136,16 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti
mavlink_global_position_int_t
globalPositionInt
;
memset
(
&
globalPositionInt
,
0
,
sizeof
(
globalPositionInt
));
// Important note: QGC only supports sending the constant GCS home position altitude for follow me.
globalPositionInt
.
time_boot_ms
=
static_cast
<
uint32_t
>
(
qgcApp
()
->
msecsSinceBoot
());
globalPositionInt
.
lat
=
motionReport
.
lat_int
;
globalPositionInt
.
lon
=
motionReport
.
lon_int
;
globalPositionInt
.
alt
=
static_cast
<
int32_t
>
(
motionReport
.
altMetersAMSL
*
1000
);
// mm
globalPositionInt
.
relative_alt
=
static_cast
<
int32_t
>
(
(
motionReport
.
altMetersAMSL
-
vehicle
->
homePosition
().
altitude
())
*
1000
);
// mm
globalPositionInt
.
vx
=
static_cast
<
int16_t
>
(
motionReport
.
vxMetersPerSec
*
100
);
// cm/sec
globalPositionInt
.
vy
=
static_cast
<
int16_t
>
(
motionReport
.
vyMetersPerSec
*
100
);
// cm/sec
globalPositionInt
.
vy
=
static_cast
<
int16_t
>
(
motionReport
.
vzMetersPerSec
*
100
);
// cm/sec
globalPositionInt
.
hdg
=
static_cast
<
uint16_t
>
(
motionReport
.
headingDegrees
*
100.0
);
// centi-degrees
globalPositionInt
.
alt
=
static_cast
<
int32_t
>
(
vehicle
->
homePosition
().
altitude
()
*
1000
);
// mm
globalPositionInt
.
relative_alt
=
static_cast
<
int32_t
>
(
0
);
// mm
globalPositionInt
.
vx
=
static_cast
<
int16_t
>
(
motionReport
.
vxMetersPerSec
*
100
);
// cm/sec
globalPositionInt
.
vy
=
static_cast
<
int16_t
>
(
motionReport
.
vyMetersPerSec
*
100
);
// cm/sec
globalPositionInt
.
vy
=
static_cast
<
int16_t
>
(
motionReport
.
vzMetersPerSec
*
100
);
// cm/sec
globalPositionInt
.
hdg
=
static_cast
<
uint16_t
>
(
motionReport
.
headingDegrees
*
100.0
);
// centi-degrees
mavlink_message_t
message
;
mavlink_msg_global_position_int_encode_chan
(
static_cast
<
uint8_t
>
(
mavlinkProtocol
->
getSystemId
()),
...
...
src/FollowMe/FollowMe.cc
View file @
de4a1528
...
...
@@ -84,6 +84,23 @@ void FollowMe::_sendGCSMotionReport()
return
;
}
// First check to see if any vehicles need follow me updates
bool
needFollowMe
=
false
;
if
(
_currentMode
==
MODE_ALWAYS
)
{
needFollowMe
=
true
;
}
else
if
(
_currentMode
==
MODE_FOLLOWME
)
{
QmlObjectListModel
*
vehicles
=
_toolbox
->
multiVehicleManager
()
->
vehicles
();
for
(
int
i
=
0
;
i
<
vehicles
->
count
();
i
++
)
{
Vehicle
*
vehicle
=
vehicles
->
value
<
Vehicle
*>
(
i
);
if
(
_isFollowFlightMode
(
vehicle
,
vehicle
->
flightMode
()))
{
needFollowMe
=
true
;
}
}
}
if
(
!
needFollowMe
)
{
return
;
}
GCSMotionReport
motionReport
=
{};
uint8_t
estimatation_capabilities
=
0
;
...
...
@@ -134,7 +151,7 @@ void FollowMe::_sendGCSMotionReport()
for
(
int
i
=
0
;
i
<
vehicles
->
count
();
i
++
)
{
Vehicle
*
vehicle
=
vehicles
->
value
<
Vehicle
*>
(
i
);
if
(
_
currentMode
==
MODE_ALWAYS
||
(
_currentMode
==
MODE_FOLLOWME
&&
_isFollowFlightMode
(
vehicle
,
vehicle
->
flightMode
()
)))
{
if
(
_
isFollowFlightMode
(
vehicle
,
vehicle
->
flightMode
(
)))
{
qCDebug
(
FollowMeLog
)
<<
"sendGCSMotionReport latInt:lonInt:altMetersAMSL"
<<
motionReport
.
lat_int
<<
motionReport
.
lon_int
<<
motionReport
.
altMetersAMSL
;
vehicle
->
firmwarePlugin
()
->
sendGCSMotionReport
(
vehicle
,
motionReport
,
estimatation_capabilities
);
}
...
...
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