mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Added user editable define for Super simple radius
This commit is contained in:
parent
74d37a3713
commit
3fcd3100cc
@ -1935,7 +1935,7 @@ static void update_navigation()
|
||||
// are we in SIMPLE mode?
|
||||
if(do_simple && g.super_simple){
|
||||
// get distance to home
|
||||
if(home_distance > 1000){ // 10m from home
|
||||
if(home_distance > SUPER_SIMPLE_RADIUS){ // 10m from home
|
||||
// we reset the angular offset to be a vector from home to the quad
|
||||
initial_simple_bearing = home_to_copter_bearing;
|
||||
//Serial.printf("ISB: %d\n", initial_simple_bearing);
|
||||
|
@ -555,6 +555,11 @@
|
||||
# define SUPER_SIMPLE DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef SUPER_SIMPLE_RADIUS
|
||||
# define SUPER_SIMPLE_RADIUS 1000
|
||||
#endif
|
||||
|
||||
|
||||
// RTL Mode
|
||||
#ifndef RTL_AUTO_LAND
|
||||
# define RTL_AUTO_LAND ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user