mirror of https://github.com/ArduPilot/ardupilot
Copter: move acro's var initialisation to roll-pitch and yaw controller initialisation
This commit is contained in:
parent
942ba0476b
commit
1abb439051
|
@ -1431,8 +1431,11 @@ bool set_yaw_mode(uint8_t new_yaw_mode)
|
||||||
|
|
||||||
switch( new_yaw_mode ) {
|
switch( new_yaw_mode ) {
|
||||||
case YAW_HOLD:
|
case YAW_HOLD:
|
||||||
|
yaw_initialised = true;
|
||||||
|
break;
|
||||||
case YAW_ACRO:
|
case YAW_ACRO:
|
||||||
yaw_initialised = true;
|
yaw_initialised = true;
|
||||||
|
acro_yaw_rate = 0;
|
||||||
break;
|
break;
|
||||||
case YAW_LOOK_AT_NEXT_WP:
|
case YAW_LOOK_AT_NEXT_WP:
|
||||||
if( ap.home_is_set ) {
|
if( ap.home_is_set ) {
|
||||||
|
@ -1660,7 +1663,14 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode)
|
||||||
|
|
||||||
switch( new_roll_pitch_mode ) {
|
switch( new_roll_pitch_mode ) {
|
||||||
case ROLL_PITCH_STABLE:
|
case ROLL_PITCH_STABLE:
|
||||||
|
roll_pitch_initialised = true;
|
||||||
|
break;
|
||||||
case ROLL_PITCH_ACRO:
|
case ROLL_PITCH_ACRO:
|
||||||
|
// reset acro level rates
|
||||||
|
acro_roll_rate = 0;
|
||||||
|
acro_pitch_rate = 0;
|
||||||
|
roll_pitch_initialised = true;
|
||||||
|
break;
|
||||||
case ROLL_PITCH_AUTO:
|
case ROLL_PITCH_AUTO:
|
||||||
case ROLL_PITCH_STABLE_OF:
|
case ROLL_PITCH_STABLE_OF:
|
||||||
case ROLL_PITCH_TOY:
|
case ROLL_PITCH_TOY:
|
||||||
|
|
|
@ -360,10 +360,6 @@ static bool set_mode(uint8_t mode)
|
||||||
set_roll_pitch_mode(ACRO_RP);
|
set_roll_pitch_mode(ACRO_RP);
|
||||||
set_throttle_mode(ACRO_THR);
|
set_throttle_mode(ACRO_THR);
|
||||||
set_nav_mode(NAV_NONE);
|
set_nav_mode(NAV_NONE);
|
||||||
// reset acro level rates
|
|
||||||
acro_roll_rate = 0;
|
|
||||||
acro_pitch_rate = 0;
|
|
||||||
acro_yaw_rate = 0;
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case STABILIZE:
|
case STABILIZE:
|
||||||
|
|
Loading…
Reference in New Issue