mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: make guided mode start at current location
This commit is contained in:
parent
21a51c8333
commit
d1afd2fb9b
@ -462,6 +462,7 @@ static void set_mode(uint8_t mode)
|
||||
set_throttle_mode(GUIDED_THR);
|
||||
set_nav_mode(GUIDED_NAV);
|
||||
wp_verify_byte = 0;
|
||||
guided_WP = current_loc;
|
||||
set_next_WP(&guided_WP);
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user