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
889a19f7
Commit
889a19f7
authored
12 years ago
by
rmackay9
Browse files
Options
Downloads
Patches
Plain Diff
ArduCopter: move scaleLongUp and scaleLongDown initialisation to init_home
parent
c8c13046
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/commands.pde
+5
-5
5 additions, 5 deletions
ArduCopter/commands.pde
with
5 additions
and
5 deletions
ArduCopter/commands.pde
+
5
−
5
View file @
889a19f7
...
...
@@ -158,11 +158,6 @@ static void set_next_WP(struct Location *wp)
// Save new altitude so we can track it for climb_rate
set_new_altitude
(
next_WP
.
alt
);
// this is used to offset the shrinking longitude as we go towards the poles
float
rads
=
(
fabs
((
float
)
next_WP
.
lat
)
/
t7
)
*
0.0174532925
;
scaleLongDown
=
cos
(
rads
);
scaleLongUp
=
1.0
f
/
cos
(
rads
);
// this is handy for the groundstation
// -----------------------------------
wp_distance
=
get_distance_cm
(
&
current_loc
,
&
next_WP
);
...
...
@@ -202,6 +197,11 @@ static void init_home()
if
(
g
.
log_bitmask
&
MASK_LOG_CMD
)
Log_Write_Cmd
(
0
,
&
home
);
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles
float
rads
=
(
fabs
((
float
)
next_WP
.
lat
)
/
t7
)
*
0.0174532925
;
scaleLongDown
=
cos
(
rads
);
scaleLongUp
=
1.0
f
/
cos
(
rads
);
// Save prev loc this makes the calcs look better before commands are loaded
prev_WP
=
home
;
...
...
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