Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
A
Ardupilot
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
OpenSource
Ardupilot
Commits
cafb38e9
"src/main/git@ssh.gitrepo.de:TsunamiKlaus/enigma.git" did not exist on "ef7461817d87f66a8bb126578d39cfe864b70e49"
Commit
cafb38e9
authored
10 years ago
by
Jonathan Challinger
Committed by
Randy Mackay
10 years ago
Browse files
Options
Downloads
Patches
Plain Diff
Copter: allow radio failsafe while disarmed so that user can be notified
parent
21beb264
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
ArduCopter/radio.pde
+2
-2
2 additions, 2 deletions
ArduCopter/radio.pde
with
2 additions
and
2 deletions
ArduCopter/radio.pde
+
2
−
2
View file @
cafb38e9
...
...
@@ -122,7 +122,7 @@ static void read_radio()
uint32_t
elapsed
=
tnow_ms
-
last_update_ms
;
// turn on throttle failsafe if no update from the RC Radio for 500ms or 2000ms if we are using RC_OVERRIDE
if
(((
!
failsafe
.
rc_override_active
&&
(
elapsed
>=
FS_RADIO_TIMEOUT_MS
))
||
(
failsafe
.
rc_override_active
&&
(
elapsed
>=
FS_RADIO_RC_OVERRIDE_TIMEOUT_MS
)))
&&
(
g
.
failsafe_throttle
&&
motors
.
armed
()
&&
!
failsafe
.
radio
))
{
(
g
.
failsafe_throttle
&&
(
ap
.
rc_receiver_present
||
motors
.
armed
()
)
&&
!
failsafe
.
radio
))
{
Log_Write_Error
(
ERROR_SUBSYSTEM_RADIO
,
ERROR_CODE_RADIO_LATE_FRAME
);
set_failsafe_radio
(
true
);
}
...
...
@@ -142,7 +142,7 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm)
if
(
throttle_pwm
<
(
uint16_t
)
g
.
failsafe_throttle_value
)
{
// if we are already in failsafe or motors not armed pass through throttle and exit
if
(
failsafe
.
radio
||
!
motors
.
armed
())
{
if
(
failsafe
.
radio
||
!
(
ap
.
rc_receiver_present
||
motors
.
armed
())
)
{
g
.
rc_3
.
set_pwm
(
throttle_pwm
);
return
;
}
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment