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
82a703a8
Commit
82a703a8
authored
Apr 25, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Initial plan load fixes
parent
6e1232db
Changes
2
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
33 additions
and
13 deletions
+33
-13
Vehicle.cc
src/Vehicle/Vehicle.cc
+30
-13
Vehicle.h
src/Vehicle/Vehicle.h
+3
-0
No files found.
src/Vehicle/Vehicle.cc
View file @
82a703a8
...
...
@@ -669,6 +669,16 @@ void Vehicle::_handleAltitude(mavlink_message_t& message)
}
}
void
Vehicle
::
_setCapabilities
(
uint64_t
capabilityBits
)
{
if
(
capabilityBits
&
MAV_PROTOCOL_CAPABILITY_MISSION_INT
)
{
_supportsMissionItemInt
=
true
;
}
_vehicleCapabilitiesKnown
=
true
;
qCDebug
(
VehicleLog
)
<<
QString
(
"Vehicle %1 MISSION_ITEM_INT"
).
arg
(
_supportsMissionItemInt
?
QStringLiteral
(
"supports"
)
:
QStringLiteral
(
"does not support"
));
}
void
Vehicle
::
_handleAutopilotVersion
(
LinkInterface
*
link
,
mavlink_message_t
&
message
)
{
Q_UNUSED
(
link
);
...
...
@@ -703,12 +713,8 @@ void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& me
emit
gitHashChanged
(
_gitHash
);
}
if
(
autopilotVersion
.
capabilities
&
MAV_PROTOCOL_CAPABILITY_MISSION_INT
)
{
qCDebug
(
VehicleLog
)
<<
"Vehicle supports MISSION_ITEM_INT"
;
_supportsMissionItemInt
=
true
;
_vehicleCapabilitiesKnown
=
true
;
_setCapabilities
(
autopilotVersion
.
capabilities
);
_startPlanRequest
();
}
}
void
Vehicle
::
_handleHilActuatorControls
(
mavlink_message_t
&
message
)
...
...
@@ -745,6 +751,7 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
if
(
ack
.
command
==
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES
&&
ack
.
result
!=
MAV_RESULT_ACCEPTED
)
{
// We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items
qCDebug
(
VehicleLog
)
<<
"Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error. Starting mission request."
;
_setCapabilities
(
0
);
_startPlanRequest
();
}
...
...
@@ -899,6 +906,14 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
_batteryFactGroup
.
cellCount
()
->
setRawValue
(
cellCount
);
}
void
Vehicle
::
_setHomePosition
(
QGeoCoordinate
&
homeCoord
)
{
if
(
homeCoord
!=
_homePosition
)
{
_homePosition
=
homeCoord
;
emit
homePositionChanged
(
_homePosition
);
}
}
void
Vehicle
::
_handleHomePosition
(
mavlink_message_t
&
message
)
{
mavlink_home_position_t
homePos
;
...
...
@@ -908,10 +923,7 @@ void Vehicle::_handleHomePosition(mavlink_message_t& message)
QGeoCoordinate
newHomePosition
(
homePos
.
latitude
/
10000000.0
,
homePos
.
longitude
/
10000000.0
,
homePos
.
altitude
/
1000.0
);
if
(
newHomePosition
!=
_homePosition
)
{
_homePosition
=
newHomePosition
;
emit
homePositionChanged
(
_homePosition
);
}
_setHomePosition
(
newHomePosition
);
}
void
Vehicle
::
_handleHeartbeat
(
mavlink_message_t
&
message
)
...
...
@@ -1625,7 +1637,11 @@ void Vehicle::_mapTrajectoryStop()
void
Vehicle
::
_startPlanRequest
(
void
)
{
if
(
!
_missionManagerInitialRequestSent
&&
_parameterManager
->
parametersReady
()
&&
_vehicleCapabilitiesKnown
)
{
if
(
_missionManagerInitialRequestSent
)
{
return
;
}
if
(
_parameterManager
->
parametersReady
()
&&
_vehicleCapabilitiesKnown
)
{
qCDebug
(
VehicleLog
)
<<
"_startPlanRequest"
;
_missionManagerInitialRequestSent
=
true
;
if
(
_settingsManager
->
appSettings
()
->
autoLoadMissions
()
->
rawValue
().
toBool
())
{
...
...
@@ -1644,7 +1660,7 @@ void Vehicle::_startPlanRequest(void)
if
(
!
_parameterManager
->
parametersReady
())
{
qCDebug
(
VehicleLog
)
<<
"Delaying _startPlanRequest due to parameters not ready"
;
}
else
if
(
!
_vehicleCapabilitiesKnown
)
{
qCDebug
(
VehicleLog
)
<<
"Delaying _startPlanRequest due to vehicle capabilities not know"
;
qCDebug
(
VehicleLog
)
<<
"Delaying _startPlanRequest due to vehicle capabilities not know
n
"
;
}
}
}
...
...
@@ -2067,6 +2083,7 @@ void Vehicle::_sendMavCommandAgain(void)
if
(
_mavCommandRetryCount
++
>
_mavCommandMaxRetryCount
)
{
if
(
queuedCommand
.
command
==
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES
)
{
// We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items
_setCapabilities
(
0
);
_startPlanRequest
();
}
...
...
@@ -2100,7 +2117,7 @@ void Vehicle::_sendMavCommandAgain(void)
}
}
}
q
Debug
(
)
<<
"Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount"
<<
queuedCommand
.
command
<<
_mavCommandRetryCount
;
q
CDebug
(
VehicleLog
)
<<
"Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount"
<<
queuedCommand
.
command
<<
_mavCommandRetryCount
;
}
_mavCommandAckTimer
.
start
();
...
...
src/Vehicle/Vehicle.h
View file @
82a703a8
...
...
@@ -673,6 +673,8 @@ public:
/// @return: true: initial request is complete, false: initial request is still in progress;
bool
initialPlanRequestComplete
(
void
)
const
{
return
_initialPlanRequestComplete
;
}
void
_setHomePosition
(
QGeoCoordinate
&
homeCoord
);
signals:
void
allLinksInactive
(
Vehicle
*
vehicle
);
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
...
...
@@ -834,6 +836,7 @@ private:
void
_commonInit
(
void
);
void
_startPlanRequest
(
void
);
void
_setupAutoDisarmSignalling
(
void
);
void
_setCapabilities
(
uint64_t
capabilityBits
);
int
_id
;
///< Mavlink system id
int
_defaultComponentId
;
...
...
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