mirror of https://github.com/ArduPilot/ardupilot
Copter: remove unused reset_stability_I
This commit is contained in:
parent
d7782e1356
commit
e5535e35b3
|
@ -1821,7 +1821,6 @@ void update_roll_pitch_mode(void)
|
|||
#if FRAME_CONFIG != HELI_FRAME
|
||||
if(g.rc_3.control_in == 0 && control_mode <= ACRO) {
|
||||
reset_rate_I();
|
||||
reset_stability_I();
|
||||
}
|
||||
#endif //HELI_FRAME
|
||||
|
||||
|
|
|
@ -1379,12 +1379,8 @@ get_throttle_surface_tracking(int16_t target_rate)
|
|||
static void reset_I_all(void)
|
||||
{
|
||||
reset_rate_I();
|
||||
reset_stability_I();
|
||||
reset_throttle_I();
|
||||
reset_optflow_I();
|
||||
|
||||
// This is the only place we reset Yaw
|
||||
g.pi_stabilize_yaw.reset_I();
|
||||
}
|
||||
|
||||
static void reset_rate_I()
|
||||
|
@ -1406,7 +1402,6 @@ static void reset_throttle_I(void)
|
|||
{
|
||||
// For Altitude Hold
|
||||
g.pi_alt_hold.reset_I();
|
||||
g.pid_throttle_rate.reset_I();
|
||||
g.pid_throttle_accel.reset_I();
|
||||
}
|
||||
|
||||
|
@ -1415,11 +1410,3 @@ static void set_accel_throttle_I_from_pilot_throttle(int16_t pilot_throttle)
|
|||
// shift difference between pilot's throttle and hover throttle into accelerometer I
|
||||
g.pid_throttle_accel.set_integrator(pilot_throttle-g.throttle_cruise);
|
||||
}
|
||||
|
||||
static void reset_stability_I(void)
|
||||
{
|
||||
// Used to balance a quad
|
||||
// This only needs to be reset during Auto-leveling in flight
|
||||
g.pi_stabilize_roll.reset_I();
|
||||
g.pi_stabilize_pitch.reset_I();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue