Plane: switch to AUTO on a DO_LAND_START MAVLink command
This commit is contained in:
parent
7ecc87a787
commit
9f32bf93d1
@ -1111,13 +1111,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAV_CMD_DO_LAND_START:
|
||||
result = MAV_RESULT_FAILED;
|
||||
//no reason to AUTO land in MANUAL mode.
|
||||
if (control_mode == MANUAL) {
|
||||
break;
|
||||
}
|
||||
|
||||
//attempt to switch to next DO_LAND_START command in the mission
|
||||
// attempt to switch to next DO_LAND_START command in the mission
|
||||
if (mission.jump_to_landing_sequence()) {
|
||||
set_mode(AUTO);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user