Tracker: handle setting of ekf origin in GCS_MAVLink

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

View File

@ -768,11 +768,6 @@ const AP_FWVersion &GCS_MAVLINK_Tracker::get_fwver() const
return tracker.fwver;
}
void GCS_MAVLINK_Tracker::set_ekf_origin(const Location& loc)
{
tracker.set_ekf_origin(loc);
}
/* dummy methods to avoid having to link against AP_Camera */
void AP_Camera::control_msg(mavlink_message_t const*) {}
void AP_Camera::configure(float, float, float, float, float, float, float) {}

View File

@ -19,7 +19,6 @@ protected:
AP_Rally *get_rally() const override { return nullptr; };
AP_Camera *get_camera() const override { return nullptr; };
const AP_FWVersion &get_fwver() const override;
void set_ekf_origin(const Location& loc) override;
uint8_t sysid_my_gcs() const override;

View File

@ -235,7 +235,6 @@ private:
bool get_home_eeprom(struct Location &loc);
void set_home_eeprom(struct Location temp);
void set_home(struct Location temp);
void set_ekf_origin(const Location& loc);
void arm_servos();
void disarm_servos();
void prepare_servos();

View File

@ -165,29 +165,6 @@ void Tracker::set_home(struct Location temp)
}
}
// sets ekf_origin if it has not been set.
// should only be used when there is no GPS to provide an absolute position
void Tracker::set_ekf_origin(const Location& loc)
{
// check location is valid
if (!check_latlng(loc)) {
return;
}
// check EKF origin has already been set
Location ekf_origin;
if (ahrs.get_origin(ekf_origin)) {
return;
}
if (!ahrs.set_origin(loc)) {
return;
}
// send ekf origin to GCS
gcs().send_ekf_origin(loc);
}
void Tracker::arm_servos()
{
hal.util->set_soft_armed(true);