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
9d48fa8d
Commit
9d48fa8d
authored
12 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
WPNav: bug fix to loiter accel calculation
Contribution from Leonard Hall
parent
29a75be4
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
libraries/AC_WPNav/AC_WPNav.cpp
+12
-8
12 additions, 8 deletions
libraries/AC_WPNav/AC_WPNav.cpp
with
12 additions
and
8 deletions
libraries/AC_WPNav/AC_WPNav.cpp
+
12
−
8
View file @
9d48fa8d
...
...
@@ -280,29 +280,33 @@ void AC_WPNav::calculate_loiter_leash_length()
// get loiter position P
float
kP
=
_pid_pos_lat
->
kP
();
// check loiter speed
if
(
_loiter_speed_cms
<
100.0
f
)
{
_loiter_speed_cms
=
100.0
f
;
}
// set loiter acceleration to 1/2 loiter speed
_loiter_accel_cms
=
_loiter_speed_cms
/
2.0
f
;
// avoid divide by zero
if
(
kP
<=
0.0
f
||
_wp_accel_cms
<=
0.0
f
)
{
_loiter_leash
=
WPNAV_MIN_LEASH_LENGTH
;
_loiter_accel_cms
=
_loiter_leash
/
2.0
f
;
// set loiter acceleration to 1/2 loiter speed
return
;
}
// calculate horiz
t
onal leash length
if
(
_loiter_speed_cms
<=
_wp_accel_cms
/
kP
)
{
// calculate horizon
t
al leash length
if
(
WPNAV_LOITER_SPEED_MAX_TO_CORRECT_ERROR
<=
_wp_accel_cms
/
kP
)
{
// linear leash length based on speed close in
_loiter_leash
=
_loiter_speed_cms
/
kP
;
_loiter_leash
=
WPNAV_LOITER_SPEED_MAX_TO_CORRECT_ERROR
/
kP
;
}
else
{
// leash length grows at sqrt of speed further out
_loiter_leash
=
(
_wp_accel_cms
/
(
2.0
f
*
kP
*
kP
))
+
(
_loiter_speed_cms
*
_loiter_speed_cms
/
(
2.0
f
*
_wp_accel_cms
));
_loiter_leash
=
(
_wp_accel_cms
/
(
2.0
f
*
kP
*
kP
))
+
(
WPNAV_LOITER_SPEED_MAX_TO_CORRECT_ERROR
*
WPNAV_LOITER_SPEED_MAX_TO_CORRECT_ERROR
/
(
2.0
f
*
_wp_accel_cms
));
}
// ensure leash is at least 1m long
if
(
_loiter_leash
<
WPNAV_MIN_LEASH_LENGTH
)
{
_loiter_leash
=
WPNAV_MIN_LEASH_LENGTH
;
}
// set loiter acceleration to 1/2 loiter speed
_loiter_accel_cms
=
_loiter_leash
/
2.0
f
;
}
///
...
...
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