Skip to content

Commit

Permalink
Copter: remove distance from home check from radio failsafe logic
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall committed Oct 12, 2015
1 parent 28347c9 commit ab83727
Showing 1 changed file with 3 additions and 12 deletions.
15 changes: 3 additions & 12 deletions ArduCopter/events.pde
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,7 @@ static void failsafe_radio_on_event()
set_mode_land_with_pause();
} else if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_RTL) {
// if failsafe_throttle is FS_THR_ENABLED_ALWAYS_RTL do RTL
if(home_distance > wp_nav.get_wp_radius()) {
// if far from home then RTL or LAND if that fails
set_mode_RTL_or_land_with_pause();
}else{
// if close to home, LAND
set_mode_land_with_pause();
}
set_mode_RTL_or_land_with_pause();
}
// failsafe_throttle must be FS_THR_ENABLED_CONTINUE_MISSION so no need to do anything
break;
Expand All @@ -43,12 +37,9 @@ static void failsafe_radio_on_event()
if(g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND) {
// if failsafe_throttle is FS_THR_ENABLED_ALWAYS_LAND then land immediately
set_mode_land_with_pause();
}else if(home_distance > wp_nav.get_wp_radius()) {
// if far from home then RTL or LAND if that fails
} else {
// otherwise RTL or land if that fails
set_mode_RTL_or_land_with_pause();
}else{
// if close to home, LAND
set_mode_land_with_pause();
}
break;
}
Expand Down

0 comments on commit ab83727

Please sign in to comment.