mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
2.0.39
Added reset for all nav I when entering manual modes. git-svn-id: https://arducopter.googlecode.com/svn/trunk@2992 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
1f974ef6d3
commit
fe3293f411
@ -794,7 +794,7 @@ static void fifty_hz_loop()
|
||||
else if (throttle_slew > 0)
|
||||
throttle_slew--;
|
||||
|
||||
throttle_slew = min((800 - throttle), throttle_slew);
|
||||
throttle_slew = min((800 - g.rc_3.control_in), throttle_slew);
|
||||
|
||||
# if HIL_MODE == HIL_MODE_DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
|
||||
@ -1578,3 +1578,4 @@ static void auto_throttle()
|
||||
//Serial.printf("wp:%d, \te:%d \tt%d \t%d\n", (int)next_WP.alt, (int)altitude_error, nav_throttle, g.rc_3.servo_out);
|
||||
}
|
||||
|
||||
|
||||
|
@ -116,8 +116,13 @@ 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_I(void)
|
||||
reset_nav_I(void)
|
||||
{
|
||||
g.pid_nav_lat.reset_I();
|
||||
g.pid_nav_lon.reset_I();
|
||||
g.pid_nav_wp.reset_I();
|
||||
g.pid_crosstrack.reset_I();
|
||||
g.pid_throttle.reset_I();
|
||||
// I removed these, they don't seem to be needed.
|
||||
}
|
||||
|
||||
|
@ -376,3 +376,4 @@ public:
|
||||
};
|
||||
|
||||
#endif // PARAMETERS_H
|
||||
|
||||
|
@ -35,7 +35,7 @@ static void failsafe_off_event()
|
||||
|
||||
// Reset control integrators
|
||||
// ---------------------
|
||||
reset_I();
|
||||
//reset_nav_I();
|
||||
|
||||
}else if (g.throttle_fs_action == 1){
|
||||
// We're back in radio contact
|
||||
|
@ -294,13 +294,6 @@ static void init_ardupilot()
|
||||
// -------------------
|
||||
init_commands();
|
||||
|
||||
// Output waypoints for confirmation
|
||||
// XXX do we need this?
|
||||
// --------------------------------
|
||||
//for(int i = 1; i < g.waypoint_total + 1; i++) {
|
||||
// gcs.send_message(MSG_COMMAND_LIST, i);
|
||||
//}
|
||||
|
||||
// set the correct flight mode
|
||||
// ---------------------------
|
||||
reset_control_switch();
|
||||
@ -381,13 +374,13 @@ static void set_mode(byte mode)
|
||||
switch(control_mode)
|
||||
{
|
||||
case ACRO:
|
||||
g.pid_throttle.reset_I();
|
||||
reset_nav_I();
|
||||
break;
|
||||
|
||||
case SIMPLE:
|
||||
case STABILIZE:
|
||||
do_loiter_at_location();
|
||||
g.pid_throttle.reset_I();
|
||||
reset_nav_I();
|
||||
break;
|
||||
|
||||
case ALT_HOLD:
|
||||
|
Loading…
Reference in New Issue
Block a user