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
ed635873
Commit
ed635873
authored
10 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
Plane: fixed failsafe pass-thru for APM2
parent
2270a904
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
ArduPlane/failsafe.pde
+10
-4
10 additions, 4 deletions
ArduPlane/failsafe.pde
with
10 additions
and
4 deletions
ArduPlane/failsafe.pde
+
10
−
4
View file @
ed635873
...
@@ -59,12 +59,18 @@ void failsafe_check(void)
...
@@ -59,12 +59,18 @@ void failsafe_check(void)
channel_throttle
->
radio_out
=
channel_throttle
->
read
();
channel_throttle
->
radio_out
=
channel_throttle
->
read
();
channel_rudder
->
radio_out
=
channel_rudder
->
read
();
channel_rudder
->
radio_out
=
channel_rudder
->
read
();
int16_t
roll
=
channel_roll
->
pwm_to_angle_dz
(
0
);
int16_t
pitch
=
channel_pitch
->
pwm_to_angle_dz
(
0
);
int16_t
rudder
=
channel_rudder
->
pwm_to_angle_dz
(
0
);
// setup secondary output channels that don't have
// setup secondary output channels that don't have
// corresponding input channels
// corresponding input channels
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_aileron
,
channel_roll
->
radio_out
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_aileron
,
roll
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_elevator
,
channel_pitch
->
radio_out
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_elevator
,
pitch
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_rudder
,
channel_rudder
->
radio_out
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_rudder
,
rudder
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_steering
,
channel_rudder
->
radio_out
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_steering
,
rudder
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_flaperon1
,
roll
);
RC_Channel_aux
::
set_servo_out
(
RC_Channel_aux
::
k_flaperon2
,
roll
);
if
(
g
.
vtail_output
!=
MIXING_DISABLED
)
{
if
(
g
.
vtail_output
!=
MIXING_DISABLED
)
{
channel_output_mixer
(
g
.
vtail_output
,
channel_pitch
->
radio_out
,
channel_rudder
->
radio_out
);
channel_output_mixer
(
g
.
vtail_output
,
channel_pitch
->
radio_out
,
channel_rudder
->
radio_out
);
...
...
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