mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: split home-set and home-locked state
This commit is contained in:
parent
1f31bd21c4
commit
3cbb88ae20
@ -436,14 +436,18 @@ public:
|
|||||||
return _home;
|
return _home;
|
||||||
}
|
}
|
||||||
|
|
||||||
enum HomeState home_status(void) const {
|
// functions to handle locking of home. Some vehicles use this to
|
||||||
return _home_status;
|
// allow GCS to lock in a home location.
|
||||||
|
void lock_home() {
|
||||||
|
_home_locked = true;
|
||||||
}
|
}
|
||||||
void set_home_status(enum HomeState new_status) {
|
bool home_is_locked() const {
|
||||||
_home_status = new_status;
|
return _home_locked;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// returns true if home is set
|
||||||
bool home_is_set(void) const {
|
bool home_is_set(void) const {
|
||||||
return _home_status != HOME_UNSET;
|
return _home_is_set;
|
||||||
}
|
}
|
||||||
|
|
||||||
// set the home location in 10e7 degrees. This should be called
|
// set the home location in 10e7 degrees. This should be called
|
||||||
@ -649,6 +653,8 @@ protected:
|
|||||||
|
|
||||||
// reference position for NED positions
|
// reference position for NED positions
|
||||||
struct Location _home;
|
struct Location _home;
|
||||||
|
bool _home_is_set :1;
|
||||||
|
bool _home_locked :1;
|
||||||
|
|
||||||
// helper trig variables
|
// helper trig variables
|
||||||
float _cos_roll, _cos_pitch, _cos_yaw;
|
float _cos_roll, _cos_pitch, _cos_yaw;
|
||||||
@ -667,9 +673,6 @@ protected:
|
|||||||
private:
|
private:
|
||||||
static AP_AHRS *_singleton;
|
static AP_AHRS *_singleton;
|
||||||
|
|
||||||
// Flag for if we have g_gps lock and have set the home location in AHRS
|
|
||||||
enum HomeState _home_status = HOME_UNSET;
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#include "AP_AHRS_DCM.h"
|
#include "AP_AHRS_DCM.h"
|
||||||
|
@ -1012,6 +1012,7 @@ void AP_AHRS_DCM::set_home(const Location &loc)
|
|||||||
{
|
{
|
||||||
_home = loc;
|
_home = loc;
|
||||||
_home.options = 0;
|
_home.options = 0;
|
||||||
|
_home_is_set = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// a relative ground position to home in meters, Down
|
// a relative ground position to home in meters, Down
|
||||||
|
@ -587,11 +587,6 @@ Vector2f AP_AHRS_NavEKF::groundspeed_vector(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_AHRS_NavEKF::set_home(const Location &loc)
|
|
||||||
{
|
|
||||||
AP_AHRS_DCM::set_home(loc);
|
|
||||||
}
|
|
||||||
|
|
||||||
// set the EKF's origin location in 10e7 degrees. This should only
|
// 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)
|
// be called when the EKF has no absolute position reference (i.e. GPS)
|
||||||
// from which to decide the origin on its own
|
// from which to decide the origin on its own
|
||||||
|
@ -125,9 +125,6 @@ public:
|
|||||||
// blended accelerometer values in the earth frame in m/s/s
|
// blended accelerometer values in the earth frame in m/s/s
|
||||||
const Vector3f &get_accel_ef_blended() const override;
|
const Vector3f &get_accel_ef_blended() const override;
|
||||||
|
|
||||||
// set home location
|
|
||||||
void set_home(const Location &loc) override;
|
|
||||||
|
|
||||||
// set the EKF's origin location in 10e7 degrees. This should only
|
// 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)
|
// be called when the EKF has no absolute position reference (i.e. GPS)
|
||||||
// from which to decide the origin on its own
|
// from which to decide the origin on its own
|
||||||
|
Loading…
Reference in New Issue
Block a user