Sub: handle setting of ekf origin in GCS_MAVLink

This commit is contained in:
Peter Barker 2018-05-16 13:39:10 +10:00 committed by Andrew Tridgell
parent 7afd056e98
commit 631e967df3
4 changed files with 0 additions and 33 deletions

View File

@ -1522,10 +1522,5 @@ const AP_FWVersion &GCS_MAVLINK_Sub::get_fwver() const
return sub.fwver;
}
void GCS_MAVLINK_Sub::set_ekf_origin(const Location& loc)
{
sub.set_ekf_origin(loc);
}
// dummy method to avoid linking AFS
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }

View File

@ -17,7 +17,6 @@ protected:
AP_Rally *get_rally() const override;
AP_Camera *get_camera() const override;
const AP_FWVersion &get_fwver() const override;
void set_ekf_origin(const Location& loc) override;
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;

View File

@ -517,7 +517,6 @@ private:
void set_home_to_current_location_inflight();
bool set_home_to_current_location(bool lock);
bool set_home(const Location& loc, bool lock);
void set_ekf_origin(const Location& loc);
bool far_from_EKF_origin(const Location& loc);
void set_system_time_from_GPS();
void exit_mission();

View File

@ -105,32 +105,6 @@ bool Sub::set_home(const Location& loc, bool lock)
return true;
}
// sets ekf_origin if it has not been set.
// should only be used when there is no GPS to provide an absolute position
void Sub::set_ekf_origin(const Location& loc)
{
// check location is valid
if (!check_latlng(loc)) {
return;
}
// check if EKF origin has already been set
Location ekf_origin;
if (ahrs.get_origin(ekf_origin)) {
return;
}
if (!ahrs.set_origin(loc)) {
return;
}
// log ahrs home and ekf origin dataflash
ahrs.Log_Write_Home_And_Origin();
// send ekf origin to GCS
gcs().send_ekf_origin(loc);
}
// far_from_EKF_origin - checks if a location is too far from the EKF origin
// returns true if too far
bool Sub::far_from_EKF_origin(const Location& loc)