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
54010dfc
Commit
54010dfc
authored
Apr 05, 2018
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Handle ARMING_REQUIRE=0
parent
a792ad5c
Changes
2
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
45 additions
and
13 deletions
+45
-13
Vehicle.cc
src/Vehicle/Vehicle.cc
+43
-13
Vehicle.h
src/Vehicle/Vehicle.h
+2
-0
No files found.
src/Vehicle/Vehicle.cc
View file @
54010dfc
...
@@ -1186,6 +1186,13 @@ void Vehicle::_handleWind(mavlink_message_t& message)
...
@@ -1186,6 +1186,13 @@ void Vehicle::_handleWind(mavlink_message_t& message)
}
}
#endif
#endif
bool
Vehicle
::
_apmArmingNotRequired
(
void
)
{
QString
armingRequireParam
(
"ARMING_REQUIRE"
);
return
_parameterManager
->
parameterExists
(
FactSystem
::
defaultComponentId
,
armingRequireParam
)
&&
_parameterManager
->
getParameter
(
FactSystem
::
defaultComponentId
,
armingRequireParam
)
->
rawValue
().
toInt
()
==
0
;
}
void
Vehicle
::
_handleSysStatus
(
mavlink_message_t
&
message
)
void
Vehicle
::
_handleSysStatus
(
mavlink_message_t
&
message
)
{
{
mavlink_sys_status_t
sysStatus
;
mavlink_sys_status_t
sysStatus
;
...
@@ -1218,6 +1225,13 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
...
@@ -1218,6 +1225,13 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
_onboardControlSensorsEnabled
=
sysStatus
.
onboard_control_sensors_enabled
;
_onboardControlSensorsEnabled
=
sysStatus
.
onboard_control_sensors_enabled
;
_onboardControlSensorsHealth
=
sysStatus
.
onboard_control_sensors_health
;
_onboardControlSensorsHealth
=
sysStatus
.
onboard_control_sensors_health
;
// ArduPilot firmare has a strange case when ARMING_REQUIRE=0. This means the vehicle is always armed but the motors are not
// really powered up until the safety button is pressed. Because of this we can't depend on the heartbeat to tell us the true
// armed (and dangerous) state. We must instead rely on SYS_STATUS telling us that the motors are enabled.
if
(
apmFirmware
()
&&
_apmArmingNotRequired
())
{
_updateArmed
(
_onboardControlSensorsEnabled
&
MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS
);
}
uint32_t
newSensorsUnhealthy
=
_onboardControlSensorsEnabled
&
~
_onboardControlSensorsHealth
;
uint32_t
newSensorsUnhealthy
=
_onboardControlSensorsEnabled
&
~
_onboardControlSensorsHealth
;
if
(
newSensorsUnhealthy
!=
_onboardControlSensorsUnhealthy
)
{
if
(
newSensorsUnhealthy
!=
_onboardControlSensorsUnhealthy
)
{
_onboardControlSensorsUnhealthy
=
newSensorsUnhealthy
;
_onboardControlSensorsUnhealthy
=
newSensorsUnhealthy
;
...
@@ -1274,20 +1288,10 @@ void Vehicle::_handleHomePosition(mavlink_message_t& message)
...
@@ -1274,20 +1288,10 @@ void Vehicle::_handleHomePosition(mavlink_message_t& message)
_setHomePosition
(
newHomePosition
);
_setHomePosition
(
newHomePosition
);
}
}
void
Vehicle
::
_
handleHeartbeat
(
mavlink_message_t
&
message
)
void
Vehicle
::
_
updateArmed
(
bool
armed
)
{
{
if
(
message
.
compid
!=
_defaultComponentId
)
{
if
(
_armed
!=
armed
)
{
return
;
_armed
=
armed
;
}
mavlink_heartbeat_t
heartbeat
;
mavlink_msg_heartbeat_decode
(
&
message
,
&
heartbeat
);
bool
newArmed
=
heartbeat
.
base_mode
&
MAV_MODE_FLAG_DECODE_POSITION_SAFETY
;
if
(
_armed
!=
newArmed
)
{
_armed
=
newArmed
;
emit
armedChanged
(
_armed
);
emit
armedChanged
(
_armed
);
// We are transitioning to the armed state, begin tracking trajectory points for the map
// We are transitioning to the armed state, begin tracking trajectory points for the map
...
@@ -1303,6 +1307,32 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message)
...
@@ -1303,6 +1307,32 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message)
}
}
}
}
}
}
}
void
Vehicle
::
_handleHeartbeat
(
mavlink_message_t
&
message
)
{
if
(
message
.
compid
!=
_defaultComponentId
)
{
return
;
}
mavlink_heartbeat_t
heartbeat
;
mavlink_msg_heartbeat_decode
(
&
message
,
&
heartbeat
);
bool
newArmed
=
heartbeat
.
base_mode
&
MAV_MODE_FLAG_DECODE_POSITION_SAFETY
;
// ArduPilot firmare has a strange case when ARMING_REQUIRE=0. This means the vehicle is always armed but the motors are not
// really powered up until the safety button is pressed. Because of this we can't depend on the heartbeat to tell us the true
// armed (and dangerous) state. We must instead rely on SYS_STATUS telling us that the motors are enabled.
if
(
apmFirmware
())
{
if
(
!
_apmArmingNotRequired
()
||
!
(
_onboardControlSensorsPresent
&
MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS
))
{
// If ARMING_REQUIRE!=0 or we haven't seen motor output status yet we use the hearbeat info for armed
_updateArmed
(
newArmed
);
}
}
else
{
// Non-ArduPilot always updates from armed state in heartbeat
_updateArmed
(
newArmed
);
}
if
(
heartbeat
.
base_mode
!=
_base_mode
||
heartbeat
.
custom_mode
!=
_custom_mode
)
{
if
(
heartbeat
.
base_mode
!=
_base_mode
||
heartbeat
.
custom_mode
!=
_custom_mode
)
{
QString
previousFlightMode
;
QString
previousFlightMode
;
...
...
src/Vehicle/Vehicle.h
View file @
54010dfc
...
@@ -987,6 +987,8 @@ private:
...
@@ -987,6 +987,8 @@ private:
void
_startPlanRequest
(
void
);
void
_startPlanRequest
(
void
);
void
_setupAutoDisarmSignalling
(
void
);
void
_setupAutoDisarmSignalling
(
void
);
void
_setCapabilities
(
uint64_t
capabilityBits
);
void
_setCapabilities
(
uint64_t
capabilityBits
);
void
_updateArmed
(
bool
armed
);
bool
_apmArmingNotRequired
(
void
);
int
_id
;
///< Mavlink system id
int
_id
;
///< Mavlink system id
int
_defaultComponentId
;
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