mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
ArduCopter: move setting of land's yaw mode to the do_land function
This commit is contained in:
parent
05e59f6f4d
commit
36f15c9555
@ -17,7 +17,6 @@ static void process_nav_command()
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
do_land();
|
||||
break;
|
||||
|
||||
@ -292,6 +291,9 @@ static void do_land()
|
||||
set_next_WP(¤t_loc);
|
||||
wp_control = LOITER_MODE;
|
||||
|
||||
// hold current heading
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
|
||||
set_throttle_mode(THROTTLE_LAND);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user