Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
B
Baitboat
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
Baitboat
Commits
b374f604
Commit
b374f604
authored
12 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
APM: simplify radio_trim code
this removes the duplicate code. Throttle trim is not changed.
parent
a90182b9
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
ArduPlane/radio.pde
+2
-23
2 additions, 23 deletions
ArduPlane/radio.pde
with
2 additions
and
23 deletions
ArduPlane/radio.pde
+
2
−
23
View file @
b374f604
...
@@ -183,35 +183,14 @@ static void trim_control_surfaces()
...
@@ -183,35 +183,14 @@ static void trim_control_surfaces()
// save to eeprom
// save to eeprom
g
.
channel_roll
.
save_eeprom
();
g
.
channel_roll
.
save_eeprom
();
g
.
channel_pitch
.
save_eeprom
();
g
.
channel_pitch
.
save_eeprom
();
g
.
channel_throttle
.
save_eeprom
();
g
.
channel_rudder
.
save_eeprom
();
g
.
channel_rudder
.
save_eeprom
();
}
}
static
void
trim_radio
()
static
void
trim_radio
()
{
{
for
(
int
y
=
0
;
y
<
30
;
y
++
)
{
for
(
u
int
8_t
y
=
0
;
y
<
30
;
y
++
)
{
read_radio
();
read_radio
();
}
}
// Store the trim values
trim_control_surfaces
();
// ---------------------
if
(
g
.
mix_mode
==
0
)
{
g
.
channel_roll
.
radio_trim
=
g
.
channel_roll
.
radio_in
;
g
.
channel_pitch
.
radio_trim
=
g
.
channel_pitch
.
radio_in
;
//g.channel_throttle.radio_trim = g.channel_throttle.radio_in;
RC_Channel_aux
::
set_radio_trim
(
RC_Channel_aux
::
k_aileron
);
}
else
{
elevon1_trim
=
ch1_temp
;
elevon2_trim
=
ch2_temp
;
uint16_t
center
=
1500
;
g
.
channel_roll
.
radio_trim
=
center
;
g
.
channel_pitch
.
radio_trim
=
center
;
}
g
.
channel_rudder
.
radio_trim
=
g
.
channel_rudder
.
radio_in
;
// save to eeprom
g
.
channel_roll
.
save_eeprom
();
g
.
channel_pitch
.
save_eeprom
();
//g.channel_throttle.save_eeprom();
g
.
channel_rudder
.
save_eeprom
();
}
}
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