From a722fd1323f7c8930ecb095a73a177ffab1dbd4f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 30 May 2018 10:52:57 +1000 Subject: [PATCH] Rover: make setting of home boolean in preparation for sanity checks --- APMrover2/APMrover2.cpp | 4 +++- APMrover2/RC_Channel.cpp | 4 +++- APMrover2/Rover.h | 4 ++-- APMrover2/commands.cpp | 8 ++++++-- APMrover2/commands_logic.cpp | 8 ++++++-- 5 files changed, 20 insertions(+), 8 deletions(-) diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index 60d88f3a03..04d1a2fc9a 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -166,7 +166,9 @@ void Rover::ahrs_update() // set home from EKF if necessary and possible if (!ahrs.home_is_set()) { - set_home_to_current_location(false); + if (!set_home_to_current_location(false)) { + // ignore this failure + } } // if using the EKF get a speed update now (from accelerometers) diff --git a/APMrover2/RC_Channel.cpp b/APMrover2/RC_Channel.cpp index eb3e4340b5..338a3425e5 100644 --- a/APMrover2/RC_Channel.cpp +++ b/APMrover2/RC_Channel.cpp @@ -93,7 +93,9 @@ void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const aux_swi // if disarmed clear mission and set home to current location if (!rover.arming.is_armed()) { rover.mode_auto.mission.clear(); - rover.set_home_to_current_location(false); + if (!rover.set_home_to_current_location(false)) { + // ignored + } return; } diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index db966c0a10..f4f8ba80e5 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -406,8 +406,8 @@ private: void update_mission(void); // commands.cpp - bool set_home_to_current_location(bool lock); - bool set_home(const Location& loc, bool lock); + bool set_home_to_current_location(bool lock) WARN_IF_UNUSED; + bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED; void update_home(); // compat.cpp diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index cd44c99adf..c60c974c1a 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -30,7 +30,9 @@ bool Rover::set_home(const Location& loc, bool lock) const bool home_was_set = ahrs.home_is_set(); // set ahrs home - ahrs.set_home(loc); + if (!ahrs.set_home(loc)) { + return false; + } if (!home_was_set) { // log new home position which mission library will pull from ahrs @@ -82,5 +84,7 @@ void Rover::update_home() return; } - ahrs.set_home(loc); + if (!ahrs.set_home(loc)) { + // silently ignored... + } } diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index 1aa9ba4ec2..34bbe0e098 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -349,9 +349,13 @@ void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd) void ModeAuto::do_set_home(const AP_Mission::Mission_Command& cmd) { if (cmd.p1 == 1 && rover.have_position) { - rover.set_home_to_current_location(false); + if (!rover.set_home_to_current_location(false)) { + // ignored... + } } else { - rover.set_home(cmd.content.location, false); + if (!rover.set_home(cmd.content.location, false)) { + // ignored... + } } }