Rover: handle setting of ekf origin in GCS_MAVLink

This commit is contained in:
Peter Barker 2018-05-16 13:38:29 +10:00 committed by Andrew Tridgell
parent fc1775df75
commit 0d3051e46a
4 changed files with 0 additions and 33 deletions

View File

@ -1388,8 +1388,3 @@ const AP_FWVersion &GCS_MAVLINK_Rover::get_fwver() const
{
return rover.fwver;
}
void GCS_MAVLINK_Rover::set_ekf_origin(const Location& loc)
{
rover.set_ekf_origin(loc);
}

View File

@ -21,7 +21,6 @@ protected:
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
AP_VisualOdom *get_visual_odom() const override;
const AP_FWVersion &get_fwver() const override;
void set_ekf_origin(const Location& loc) override;
uint8_t sysid_my_gcs() const override;

View File

@ -427,7 +427,6 @@ private:
void update_home_from_EKF();
bool set_home_to_current_location(bool lock);
bool set_home(const Location& loc, bool lock);
void set_ekf_origin(const Location& loc);
void set_system_time_from_GPS();
void update_home();

View File

@ -88,32 +88,6 @@ bool Rover::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 Rover::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);
}
// checks if we should update ahrs/RTL home position from GPS
void Rover::set_system_time_from_GPS()
{