mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
converted auto land to use the mission planner version
Removed gate that looked for already set control_mode. Wasn't compatible with failsafe
This commit is contained in:
parent
12493d6431
commit
cf5e0b3a1b
@ -426,10 +426,11 @@ static void startup_ground(void)
|
|||||||
|
|
||||||
static void set_mode(byte mode)
|
static void set_mode(byte mode)
|
||||||
{
|
{
|
||||||
if(control_mode == mode){
|
//if(control_mode == mode){
|
||||||
// don't switch modes if we are already in the correct mode.
|
// don't switch modes if we are already in the correct mode.
|
||||||
return;
|
// Serial.print("Double mode\n");
|
||||||
}
|
//return;
|
||||||
|
//}
|
||||||
|
|
||||||
// if we don't have GPS lock
|
// if we don't have GPS lock
|
||||||
if(home_is_set == false){
|
if(home_is_set == false){
|
||||||
@ -458,6 +459,9 @@ static void set_mode(byte mode)
|
|||||||
// do not auto_land if we are leaving RTL
|
// do not auto_land if we are leaving RTL
|
||||||
auto_land_timer = 0;
|
auto_land_timer = 0;
|
||||||
|
|
||||||
|
// if we change modes, we must clear landed flag
|
||||||
|
land_complete = false;
|
||||||
|
|
||||||
// debug to Serial terminal
|
// debug to Serial terminal
|
||||||
Serial.println(flight_mode_strings[control_mode]);
|
Serial.println(flight_mode_strings[control_mode]);
|
||||||
|
|
||||||
@ -531,12 +535,10 @@ static void set_mode(byte mode)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case LAND:
|
case LAND:
|
||||||
land_complete = false;
|
yaw_mode = LOITER_YAW;
|
||||||
yaw_mode = YAW_HOLD;
|
roll_pitch_mode = LOITER_RP;
|
||||||
roll_pitch_mode = ROLL_PITCH_AUTO;
|
|
||||||
throttle_mode = THROTTLE_AUTO;
|
throttle_mode = THROTTLE_AUTO;
|
||||||
next_WP = current_loc;
|
do_land();
|
||||||
next_WP.alt = 0;
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case RTL:
|
case RTL:
|
||||||
|
Loading…
Reference in New Issue
Block a user