mirror of https://github.com/ArduPilot/ardupilot
Made RTL go up 10m for failsafe
This commit is contained in:
parent
17873eb09c
commit
8f3c577e47
|
@ -12,16 +12,23 @@ static void failsafe_on_event()
|
||||||
case AUTO:
|
case AUTO:
|
||||||
if (g.throttle_fs_action == 1) {
|
if (g.throttle_fs_action == 1) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
|
// send up up 10m
|
||||||
|
next_WP.alt += 1000;
|
||||||
}
|
}
|
||||||
// 2 = Stay in AUTO and ignore failsafe
|
// 2 = Stay in AUTO and ignore failsafe
|
||||||
|
|
||||||
default:
|
default:
|
||||||
if(home_is_set == true){
|
if(home_is_set == true){
|
||||||
if ((get_distance(¤t_loc, &home) > 15) && (current_loc.alt > 400)){
|
// home distance is in meters
|
||||||
|
// This is to prevent accidental RTL
|
||||||
|
if ((home_distance > 15) && (current_loc.alt > 400)){
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
// override safety
|
// send up up 10m
|
||||||
motor_auto_armed = true;
|
next_WP.alt += 1000;
|
||||||
}
|
}
|
||||||
|
}else{
|
||||||
|
// We have no GPS so we must land
|
||||||
|
set_mode(LAND);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue