mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Some nice updates to Rate based nav according to the simulation.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2316 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
41fc9d60ca
commit
73129c52b9
@ -436,10 +436,10 @@ byte slow_loopCounter;
|
|||||||
int superslow_loopCounter;
|
int superslow_loopCounter;
|
||||||
byte flight_timer; // for limiting the execution of flight mode thingys
|
byte flight_timer; // for limiting the execution of flight mode thingys
|
||||||
|
|
||||||
//unsigned long nav_loopTimer; // used to track the elapsed ime for GPS nav
|
unsigned long nav_loopTimer; // used to track the elapsed ime for GPS nav
|
||||||
unsigned long nav2_loopTimer; // used to track the elapsed ime for GPS nav
|
unsigned long nav2_loopTimer; // used to track the elapsed ime for GPS nav
|
||||||
|
|
||||||
//unsigned long dTnav; // Delta Time in milliseconds for navigation computations
|
unsigned long dTnav; // Delta Time in milliseconds for navigation computations
|
||||||
unsigned long dTnav2; // Delta Time in milliseconds for navigation computations
|
unsigned long dTnav2; // Delta Time in milliseconds for navigation computations
|
||||||
unsigned long elapsedTime; // for doing custom events
|
unsigned long elapsedTime; // for doing custom events
|
||||||
float load; // % MCU cycles used
|
float load; // % MCU cycles used
|
||||||
@ -589,8 +589,8 @@ void medium_loop()
|
|||||||
g_gps->new_data = false;
|
g_gps->new_data = false;
|
||||||
|
|
||||||
// we are not tracking I term on navigation, so this isn't needed
|
// we are not tracking I term on navigation, so this isn't needed
|
||||||
//dTnav = millis() - nav_loopTimer;
|
dTnav = millis() - nav_loopTimer;
|
||||||
//nav_loopTimer = millis();
|
nav_loopTimer = millis();
|
||||||
|
|
||||||
// calculate the copter's desired bearing and WP distance
|
// calculate the copter's desired bearing and WP distance
|
||||||
// ------------------------------------------------------
|
// ------------------------------------------------------
|
||||||
@ -1145,8 +1145,12 @@ void update_navigation()
|
|||||||
// calc a pitch to the target
|
// calc a pitch to the target
|
||||||
calc_loiter_nav();
|
calc_loiter_nav();
|
||||||
|
|
||||||
} else {
|
// rotate pitch and roll to the copter frame of reference
|
||||||
|
calc_loiter_output();
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// how far are we from the ideal trajectory?
|
||||||
|
// this pushes us back on course
|
||||||
update_crosstrack();
|
update_crosstrack();
|
||||||
|
|
||||||
// calc a rate dampened pitch to the target
|
// calc a rate dampened pitch to the target
|
||||||
@ -1156,8 +1160,6 @@ void update_navigation()
|
|||||||
calc_nav_output();
|
calc_nav_output();
|
||||||
}
|
}
|
||||||
|
|
||||||
//limit our copter pitch - this will change if we go to a fully rate limited approach.
|
|
||||||
limit_nav_pitch_roll(g.pitch_max.get());
|
|
||||||
|
|
||||||
// this tracks a location so the copter is always pointing towards it.
|
// this tracks a location so the copter is always pointing towards it.
|
||||||
if(yaw_tracking == MAV_ROI_LOCATION){
|
if(yaw_tracking == MAV_ROI_LOCATION){
|
||||||
|
@ -390,16 +390,16 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef NAV_WP_P
|
#ifndef NAV_WP_P
|
||||||
# define NAV_WP_P 4.0
|
# define NAV_WP_P 3.0 // for 4.5 ms error = 13.5 pitch
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_WP_I
|
#ifndef NAV_WP_I
|
||||||
# define NAV_WP_I 0.15 // leave 0
|
# define NAV_WP_I 0.5 // this is a fast ramp up
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_WP_D
|
#ifndef NAV_WP_D
|
||||||
# define NAV_WP_D 10 // not sure about at all
|
# define NAV_WP_D .1 // slight dampening of a few degrees at most
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_WP_IMAX
|
#ifndef NAV_WP_IMAX
|
||||||
# define NAV_WP_IMAX 20 // 20 degrees
|
# define NAV_WP_IMAX 40 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -84,7 +84,6 @@ void output_motors_disarmed()
|
|||||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void output_motor_test()
|
void output_motor_test()
|
||||||
{
|
{
|
||||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
||||||
|
@ -67,13 +67,14 @@ void calc_loiter_nav()
|
|||||||
lat_error = constrain(lat_error, -DIST_ERROR_MAX, DIST_ERROR_MAX); // +- 20m max error
|
lat_error = constrain(lat_error, -DIST_ERROR_MAX, DIST_ERROR_MAX); // +- 20m max error
|
||||||
|
|
||||||
// Convert distance into ROLL X
|
// Convert distance into ROLL X
|
||||||
//nav_lon = long_error * g.pid_nav_lon.kP(); // 1800 * 2 = 3600 or 36°
|
|
||||||
nav_lon = g.pid_nav_lon.get_pid(long_error, dTnav2, 1.0);
|
nav_lon = g.pid_nav_lon.get_pid(long_error, dTnav2, 1.0);
|
||||||
|
|
||||||
// PITCH Y
|
// PITCH Y
|
||||||
//nav_lat = lat_error * g.pid_nav_lat.kP(); // 1800 * 2 = 3600 or 36°
|
|
||||||
nav_lat = g.pid_nav_lat.get_pid(lat_error, dTnav2, 1.0); // invert lat (for pitch)
|
nav_lat = g.pid_nav_lat.get_pid(lat_error, dTnav2, 1.0); // invert lat (for pitch)
|
||||||
|
}
|
||||||
|
|
||||||
|
void calc_loiter_output()
|
||||||
|
{
|
||||||
// rotate the vector
|
// rotate the vector
|
||||||
nav_roll = (float)nav_lon * sin_yaw_y - (float)nav_lat * -cos_yaw_x;
|
nav_roll = (float)nav_lon * sin_yaw_y - (float)nav_lat * -cos_yaw_x;
|
||||||
// BAD
|
// BAD
|
||||||
@ -101,6 +102,12 @@ void calc_loiter_nav()
|
|||||||
//EAST -1000 * -1 + 1000 * 0 = 1000 // pitch back
|
//EAST -1000 * -1 + 1000 * 0 = 1000 // pitch back
|
||||||
//SOUTH -1000 * 0 + 1000 * -1 = -1000 // pitch forward
|
//SOUTH -1000 * 0 + 1000 * -1 = -1000 // pitch forward
|
||||||
|
|
||||||
|
//limit our copter pitch - this will change if we go to a fully rate limited approach.
|
||||||
|
|
||||||
|
long pmax = g.pitch_max.get();
|
||||||
|
nav_roll = constrain(nav_roll, -pmax, pmax);
|
||||||
|
nav_pitch = constrain(nav_pitch, -pmax, pmax);
|
||||||
|
//limit_nav_pitch_roll(g.pitch_max.get());
|
||||||
}
|
}
|
||||||
|
|
||||||
void calc_simple_nav()
|
void calc_simple_nav()
|
||||||
@ -154,26 +161,18 @@ void calc_rate_nav()
|
|||||||
long target_error = target_bearing - g_gps->ground_course;
|
long target_error = target_bearing - g_gps->ground_course;
|
||||||
target_error = wrap_180(target_error);
|
target_error = wrap_180(target_error);
|
||||||
|
|
||||||
// calc the cos of the error to tell how fast we are moving towards the target
|
// calc the cos of the error to tell how fast we are moving towards the target in cm
|
||||||
int groundspeed = (float)g_gps->ground_speed * cos(radians((float)target_error/100));
|
int groundspeed = (float)g_gps->ground_speed * cos(radians((float)target_error/100));
|
||||||
|
|
||||||
// change to rate error
|
// change to rate error
|
||||||
// we want to be going 450cm/s
|
// we want to be going 450cm/s
|
||||||
int nav_lat = WAYPOINT_SPEED - groundspeed;
|
int error = constrain(WAYPOINT_SPEED - groundspeed, -1000, 1000);
|
||||||
nav_lat = constrain(nav_lat, -1800, 1800);
|
|
||||||
|
|
||||||
// Scale response by kP
|
// Scale response by kP
|
||||||
long nav_lat = g.pid_nav_wp.kP() * nav_lat;
|
long nav_lat = g.pid_nav_wp.get_pid(error, dTnav, 1.0);
|
||||||
int dampening = g.pid_nav_wp.kD() * (groundspeed - last_ground_speed);
|
|
||||||
|
|
||||||
// remember our old speed
|
|
||||||
last_ground_speed = groundspeed;
|
|
||||||
|
|
||||||
// dampen our response
|
|
||||||
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, -4000, 4000); // +- max error
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user