mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
updated alternative rate nav function.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2281 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
efc4584e92
commit
4646b76217
@ -129,7 +129,7 @@ void calc_nav_output()
|
|||||||
void calc_rate_nav()
|
void calc_rate_nav()
|
||||||
{
|
{
|
||||||
// calc distance error
|
// calc distance error
|
||||||
nav_lat = constrain((wp_distance * 100), -1800, 1800); // +- 20m max error
|
nav_lat = min((wp_distance * 100), 1800); // +- 20m max error
|
||||||
|
|
||||||
// Scale response by kP
|
// Scale response by kP
|
||||||
nav_lat *= g.pid_nav_lat.kP(); // 1800 * 2 = 3600 or 36°
|
nav_lat *= g.pid_nav_lat.kP(); // 1800 * 2 = 3600 or 36°
|
||||||
@ -159,17 +159,18 @@ void calc_rate_nav()
|
|||||||
|
|
||||||
// change to rate error
|
// change to rate error
|
||||||
// we want to be going 450cm/s
|
// we want to be going 450cm/s
|
||||||
int error = WAYPOINT_SPEED - groundspeed;
|
int nav_lat = WAYPOINT_SPEED - groundspeed;
|
||||||
|
nav_lat = constrain(nav_lat, -1800, 1800);
|
||||||
|
|
||||||
// Scale response by kP
|
// Scale response by kP
|
||||||
long nav_lat = g.pid_nav_wp.kP() * error;
|
long nav_lat = g.pid_nav_wp.kP() * nav_lat;
|
||||||
int dampening = g.pid_nav_wp.kD() * (groundspeed - last_ground_speed);
|
int dampening = g.pid_nav_wp.kD() * (groundspeed - last_ground_speed);
|
||||||
|
|
||||||
// remember our old speed
|
// remember our old speed
|
||||||
last_ground_speed = groundspeed;
|
last_ground_speed = groundspeed;
|
||||||
|
|
||||||
// dampen our response
|
// dampen our response
|
||||||
nav_lat -= constrain(dampening, -1800, 1800); // +- max error
|
nav_lat -= dampening; // +- max error
|
||||||
|
|
||||||
// limit our output
|
// limit our output
|
||||||
nav_lat = constrain(nav_lat, -1800, 1800); // +- max error
|
nav_lat = constrain(nav_lat, -1800, 1800); // +- max error
|
||||||
|
Loading…
Reference in New Issue
Block a user