Copter: initialise roll, pitch, yaw modes to stabilize

This fixes a bug in which the stabilize throttle controller would be
non-tilt compensated until the user switched to another flight mode and
back again
This commit is contained in:
Randy Mackay 2013-11-06 15:32:01 +09:00
parent ae87759e6d
commit 633e91b7d4
3 changed files with 11 additions and 5 deletions

View File

@ -656,11 +656,11 @@ static int32_t baro_alt;
// Each Flight mode is a unique combination of these modes
//
// The current desired control scheme for Yaw
static uint8_t yaw_mode;
static uint8_t yaw_mode = STABILIZE_YAW;
// The current desired control scheme for roll and pitch / navigation
static uint8_t roll_pitch_mode;
static uint8_t roll_pitch_mode = STABILIZE_RP;
// The current desired control scheme for altitude hold
static uint8_t throttle_mode;
static uint8_t throttle_mode = STABILIZE_THR;
////////////////////////////////////////////////////////////////////////////////

View File

@ -532,6 +532,12 @@
// Flight mode roll, pitch, yaw, throttle and navigation definitions
// Stabilize Mode
#ifndef STABILIZE_YAW
# define STABILIZE_YAW YAW_HOLD
#endif
#ifndef STABILIZE_RP
# define STABILIZE_RP ROLL_PITCH_STABLE
#endif
#ifndef STABILIZE_THR
# define STABILIZE_THR THROTTLE_MANUAL_TILT_COMPENSATED
#endif

View File

@ -352,8 +352,8 @@ static bool set_mode(uint8_t mode)
case STABILIZE:
success = true;
set_yaw_mode(YAW_HOLD);
set_roll_pitch_mode(ROLL_PITCH_STABLE);
set_yaw_mode(STABILIZE_YAW);
set_roll_pitch_mode(STABILIZE_RP);
set_throttle_mode(STABILIZE_THR);
set_nav_mode(NAV_NONE);
break;