mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
2.0.40 -
added separate reset for rate based nav. This allows Wind and throttle Iterms to avoid being cleared when moving between nav modes. git-svn-id: https://arducopter.googlecode.com/svn/trunk@3257 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
453c474481
commit
135dfd1fd4
@ -147,18 +147,23 @@ get_rate_yaw(long target_rate)
|
||||
|
||||
// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc.
|
||||
// Keeps outdated data out of our calculations
|
||||
static void reset_nav_I(void)
|
||||
static void reset_hold_I(void)
|
||||
{
|
||||
g.pi_loiter_lat.reset_I();
|
||||
g.pi_loiter_lat.reset_I();
|
||||
|
||||
g.pi_nav_lat.reset_I();
|
||||
g.pi_nav_lon.reset_I();
|
||||
|
||||
g.pi_crosstrack.reset_I();
|
||||
g.pi_throttle.reset_I();
|
||||
}
|
||||
|
||||
// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc.
|
||||
// Keeps outdated data out of our calculations
|
||||
static void reset_nav_I(void)
|
||||
{
|
||||
g.pi_nav_lat.reset_I();
|
||||
g.pi_nav_lon.reset_I();
|
||||
}
|
||||
|
||||
|
||||
/*************************************************************
|
||||
throttle control
|
||||
|
@ -33,9 +33,6 @@ static void failsafe_off_event()
|
||||
// --------------------------------------------------------
|
||||
reset_control_switch();
|
||||
|
||||
// Reset control integrators
|
||||
// ---------------------
|
||||
//reset_nav_I();
|
||||
|
||||
}else if (g.throttle_fs_action == 1){
|
||||
// We're back in radio contact
|
||||
|
@ -363,6 +363,7 @@ static void set_mode(byte mode)
|
||||
|
||||
// most modes do not calculate crosstrack correction
|
||||
xtrack_enabled = false;
|
||||
reset_nav_I();
|
||||
|
||||
switch(control_mode)
|
||||
{
|
||||
@ -370,21 +371,21 @@ static void set_mode(byte mode)
|
||||
yaw_mode = YAW_ACRO;
|
||||
roll_pitch_mode = ROLL_PITCH_ACRO;
|
||||
throttle_mode = THROTTLE_MANUAL;
|
||||
reset_nav_I();
|
||||
reset_hold_I();
|
||||
break;
|
||||
|
||||
case STABILIZE:
|
||||
yaw_mode = YAW_HOLD;
|
||||
roll_pitch_mode = ROLL_PITCH_STABLE;
|
||||
throttle_mode = THROTTLE_MANUAL;
|
||||
reset_nav_I();
|
||||
reset_hold_I();
|
||||
break;
|
||||
|
||||
case SIMPLE:
|
||||
yaw_mode = SIMPLE_YAW;
|
||||
roll_pitch_mode = SIMPLE_RP;
|
||||
throttle_mode = SIMPLE_THR;
|
||||
reset_nav_I();
|
||||
reset_hold_I();
|
||||
break;
|
||||
|
||||
case ALT_HOLD:
|
||||
@ -396,7 +397,7 @@ static void set_mode(byte mode)
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
reset_nav_I();
|
||||
reset_hold_I();
|
||||
yaw_mode = AUTO_YAW;
|
||||
roll_pitch_mode = AUTO_RP;
|
||||
throttle_mode = AUTO_THR;
|
||||
|
Loading…
Reference in New Issue
Block a user