Better Loiter PIDs

Fixed RTL overshoot bug
This commit is contained in:
Jason Short 2011-10-06 17:42:09 -07:00
parent f6fe6fde33
commit 167df79b49
2 changed files with 7 additions and 9 deletions

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduCopter V2.0.46 Beta"
#define THISFIRMWARE "ArduCopter V2.0.47 Beta"
/*
ArduCopter Version 2.0 Beta
Authors: Jason Short
@ -1124,7 +1124,7 @@ static void update_navigation()
break;
case RTL:
if(wp_distance > 4){
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
// calculates desired Yaw
// XXX this is an experiment
#if FRAME_CONFIG == HELI_FRAME
@ -1402,8 +1402,6 @@ static void update_nav_wp()
calc_loiter_pitch_roll();
} else {
// for long journey's reset the wind resopnse
// it assumes we are standing still.
// use error as the desired rate towards the target
calc_nav_rate(g.waypoint_speed_max);
// rotate pitch and roll to the copter frame of reference

View File

@ -467,23 +467,23 @@
// Navigation control gains
//
#ifndef LOITER_P
# define LOITER_P 1.0 //
# define LOITER_P .5 //
#endif
#ifndef LOITER_I
# define LOITER_I 0.01 //
# define LOITER_I 0.0 //
#endif
#ifndef LOITER_IMAX
# define LOITER_IMAX 12 // degrees°
#endif
#ifndef NAV_P
# define NAV_P 2.0 // for 4.5 ms error = 13.5 pitch
# define NAV_P 4.0 //
#endif
#ifndef NAV_I
# define NAV_I 0.10 // this feels really low, 4s to move 1 degree pitch...
# define NAV_I 0.25 // this feels really low, 4s to move 1 degree pitch...
#endif
#ifndef NAV_IMAX
# define NAV_IMAX 16 // degrees
# define NAV_IMAX 20 // degrees
#endif
#ifndef WAYPOINT_SPEED_MAX