mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: make setting of home boolean in preparation for sanity checks
This commit is contained in:
parent
b97f9cc555
commit
2e403bfd52
|
@ -462,7 +462,7 @@ public:
|
|||
// set the home location in 10e7 degrees. This should be called
|
||||
// when the vehicle is at this position. It is assumed that the
|
||||
// current barometer and GPS altitudes correspond to this altitude
|
||||
virtual void set_home(const Location &loc) = 0;
|
||||
virtual bool set_home(const Location &loc) WARN_IF_UNUSED = 0;
|
||||
|
||||
// set the EKF's origin location in 10e7 degrees. This should only
|
||||
// be called when the EKF has no absolute position reference (i.e. GPS)
|
||||
|
|
|
@ -1031,7 +1031,7 @@ bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const
|
|||
return ret;
|
||||
}
|
||||
|
||||
void AP_AHRS_DCM::set_home(const Location &loc)
|
||||
bool AP_AHRS_DCM::set_home(const Location &loc)
|
||||
{
|
||||
_home = loc;
|
||||
_home_is_set = true;
|
||||
|
@ -1042,6 +1042,8 @@ void AP_AHRS_DCM::set_home(const Location &loc)
|
|||
// send new home and ekf origin to GCS
|
||||
gcs().send_home();
|
||||
gcs().send_ekf_origin();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// a relative ground position to home in meters, Down
|
||||
|
|
|
@ -96,7 +96,7 @@ public:
|
|||
|
||||
bool use_compass() override;
|
||||
|
||||
void set_home(const Location &loc) override;
|
||||
bool set_home(const Location &loc) override WARN_IF_UNUSED;
|
||||
void estimate_wind(void);
|
||||
|
||||
// is the AHRS subsystem healthy?
|
||||
|
|
Loading…
Reference in New Issue