Plane: handle setting of ekf origin in GCS_MAVLink
This commit is contained in:
parent
9dce133938
commit
7afd056e98
@ -1831,8 +1831,3 @@ const AP_FWVersion &GCS_MAVLINK_Plane::get_fwver() const
|
|||||||
{
|
{
|
||||||
return plane.fwver;
|
return plane.fwver;
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK_Plane::set_ekf_origin(const Location& loc)
|
|
||||||
{
|
|
||||||
plane.set_ekf_origin(loc);
|
|
||||||
}
|
|
||||||
|
@ -24,7 +24,6 @@ protected:
|
|||||||
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
||||||
AP_Rally *get_rally() const override;
|
AP_Rally *get_rally() const override;
|
||||||
const AP_FWVersion &get_fwver() const override;
|
const AP_FWVersion &get_fwver() const override;
|
||||||
void set_ekf_origin(const Location& loc) override;
|
|
||||||
|
|
||||||
uint8_t sysid_my_gcs() const override;
|
uint8_t sysid_my_gcs() const override;
|
||||||
|
|
||||||
|
@ -835,7 +835,6 @@ private:
|
|||||||
void set_guided_WP(void);
|
void set_guided_WP(void);
|
||||||
void init_home();
|
void init_home();
|
||||||
void update_home();
|
void update_home();
|
||||||
void set_ekf_origin(const Location& loc);
|
|
||||||
void do_RTL(int32_t alt);
|
void do_RTL(int32_t alt);
|
||||||
bool verify_takeoff();
|
bool verify_takeoff();
|
||||||
bool verify_loiter_unlim();
|
bool verify_loiter_unlim();
|
||||||
|
@ -148,29 +148,3 @@ void Plane::update_home()
|
|||||||
}
|
}
|
||||||
barometer.update_calibration();
|
barometer.update_calibration();
|
||||||
}
|
}
|
||||||
|
|
||||||
// sets ekf_origin if it has not been set.
|
|
||||||
// should only be used when there is no GPS to provide an absolute position
|
|
||||||
void Plane::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);
|
|
||||||
}
|
|
||||||
|
Loading…
Reference in New Issue
Block a user