mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: autotune restore orig pids if user changes flight mode
This commit is contained in:
parent
f13b45467f
commit
c59dee045c
@ -1602,6 +1602,7 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode)
|
|||||||
|
|
||||||
// if initialisation has been successful update the yaw mode
|
// if initialisation has been successful update the yaw mode
|
||||||
if( roll_pitch_initialised ) {
|
if( roll_pitch_initialised ) {
|
||||||
|
exit_roll_pitch_mode(roll_pitch_mode);
|
||||||
roll_pitch_mode = new_roll_pitch_mode;
|
roll_pitch_mode = new_roll_pitch_mode;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1609,6 +1610,17 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode)
|
|||||||
return roll_pitch_initialised;
|
return roll_pitch_initialised;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// exit_roll_pitch_mode - peforms any code required when exiting the current roll-pitch mode
|
||||||
|
void exit_roll_pitch_mode(uint8_t old_roll_pitch_mode)
|
||||||
|
{
|
||||||
|
#if AUTOTUNE == ENABLED
|
||||||
|
if (old_roll_pitch_mode == ROLL_PITCH_AUTOTUNE) {
|
||||||
|
auto_tune_stop();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// update_roll_pitch_mode - run high level roll and pitch controllers
|
// update_roll_pitch_mode - run high level roll and pitch controllers
|
||||||
// 100hz update rate
|
// 100hz update rate
|
||||||
void update_roll_pitch_mode(void)
|
void update_roll_pitch_mode(void)
|
||||||
|
Loading…
Reference in New Issue
Block a user