Sub: make setting of home boolean in preparation for sanity checks

This commit is contained in:
Peter Barker 2018-05-30 10:47:13 +10:00 committed by Peter Barker
parent 5ae52038fa
commit 8937ef3190
6 changed files with 28 additions and 12 deletions

View File

@ -945,7 +945,9 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
mavlink_set_home_position_t packet;
mavlink_msg_set_home_position_decode(msg, &packet);
if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) {
sub.set_home_to_current_location(true);
if (!sub.set_home_to_current_location(true)) {
// ignore this failure
}
} else {
// sanity check location
if (!check_latlng(packet.latitude, packet.longitude)) {
@ -958,7 +960,9 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
if (sub.far_from_EKF_origin(new_home_loc)) {
break;
}
sub.set_home(new_home_loc, true);
if (!sub.set_home(new_home_loc, true)) {
// silently ignored
}
}
break;
}

View File

@ -32,8 +32,8 @@ protected:
bool vehicle_initialised() const override;
bool set_home_to_current_location(bool lock) override;
bool set_home(const Location& loc, bool lock) override;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
private:

View File

@ -507,8 +507,8 @@ private:
void userhook_SuperSlowLoop();
void update_home_from_EKF();
void set_home_to_current_location_inflight();
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;
bool far_from_EKF_origin(const Location& loc);
void exit_mission();
bool verify_loiter_unlimited();

View File

@ -13,7 +13,9 @@ void Sub::update_home_from_EKF()
set_home_to_current_location_inflight();
} else {
// move home to current ekf location (this will set home_state to HOME_SET)
set_home_to_current_location(false);
if (!set_home_to_current_location(false)) {
// ignore this failure
}
}
}
@ -25,7 +27,9 @@ void Sub::set_home_to_current_location_inflight()
if (inertial_nav.get_location(temp_loc)) {
const struct Location &ekf_origin = inertial_nav.get_origin();
temp_loc.alt = ekf_origin.alt;
set_home(temp_loc, false);
if (!set_home(temp_loc, false)) {
// ignore this failure
}
}
}
@ -65,7 +69,9 @@ bool Sub::set_home(const Location& loc, bool lock)
const bool home_was_set = ahrs.home_is_set();
// set ahrs home (used for RTL)
ahrs.set_home(loc);
if (!ahrs.set_home(loc)) {
return false;
}
// init inav and compass declination
if (!home_was_set) {

View File

@ -765,10 +765,14 @@ void Sub::do_change_speed(const AP_Mission::Mission_Command& cmd)
void Sub::do_set_home(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 == 1 || (cmd.content.location.lat == 0 && cmd.content.location.lng == 0 && cmd.content.location.alt == 0)) {
set_home_to_current_location(false);
if (!set_home_to_current_location(false)) {
// silently ignore this failure
}
} else {
if (!far_from_EKF_origin(cmd.content.location)) {
set_home(cmd.content.location, false);
if (!set_home(cmd.content.location, false)) {
// silently ignore this failure
}
}
}
}

View File

@ -52,7 +52,9 @@ bool Sub::init_arm_motors(AP_Arming::ArmingMethod method)
// Log_Write_Event(DATA_EKF_ALT_RESET);
} else if (ahrs.home_is_set() && !ahrs.home_is_locked()) {
// Reset home position if it has already been set before (but not locked)
set_home_to_current_location(false);
if (!set_home_to_current_location(false)) {
// ignore this failure
}
}
// enable gps velocity based centrefugal force compensation