Switched to set_next_WP for mode switches

This commit is contained in:
Jason Short 2012-01-10 23:40:39 -08:00
parent 30f5ecda54
commit 7933492fec
1 changed files with 5 additions and 9 deletions

View File

@ -321,7 +321,7 @@ static void init_ardupilot()
#endif #endif
// initialise sonar // initialise sonar
#if HIL_MODE != HIL_MODE_ATTITUDE && CONFIG_SONAR == ENABLED #if CONFIG_SONAR == ENABLED
init_sonar(); init_sonar();
#endif #endif
@ -490,9 +490,7 @@ static void set_mode(byte mode)
roll_pitch_mode = ALT_HOLD_RP; roll_pitch_mode = ALT_HOLD_RP;
throttle_mode = ALT_HOLD_THR; throttle_mode = ALT_HOLD_THR;
next_WP = current_loc; set_next_WP(&current_loc);
// 1m is the alt hold limit
next_WP.alt = max(next_WP.alt, 100);
break; break;
case AUTO: case AUTO:
@ -508,9 +506,7 @@ static void set_mode(byte mode)
yaw_mode = CIRCLE_YAW; yaw_mode = CIRCLE_YAW;
roll_pitch_mode = CIRCLE_RP; roll_pitch_mode = CIRCLE_RP;
throttle_mode = CIRCLE_THR; throttle_mode = CIRCLE_THR;
next_WP = current_loc; set_next_WP(&current_loc);
// reset the desired circle angle
circle_angle = 0; circle_angle = 0;
break; break;
@ -518,14 +514,14 @@ static void set_mode(byte mode)
yaw_mode = LOITER_YAW; yaw_mode = LOITER_YAW;
roll_pitch_mode = LOITER_RP; roll_pitch_mode = LOITER_RP;
throttle_mode = LOITER_THR; throttle_mode = LOITER_THR;
next_WP = current_loc; set_next_WP(&current_loc);
break; break;
case POSITION: case POSITION:
yaw_mode = YAW_HOLD; yaw_mode = YAW_HOLD;
roll_pitch_mode = ROLL_PITCH_AUTO; roll_pitch_mode = ROLL_PITCH_AUTO;
throttle_mode = THROTTLE_MANUAL; throttle_mode = THROTTLE_MANUAL;
next_WP = current_loc; set_next_WP(&current_loc);
break; break;
case GUIDED: case GUIDED: