mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: supply missing get_relative_position_D_home
Simply returns the baro altitude (like EKF does if it lacks position)
This commit is contained in:
parent
24647fb2b0
commit
4ed7fb154f
|
@ -1003,6 +1003,12 @@ void AP_AHRS_DCM::set_home(const Location &loc)
|
||||||
_home.options = 0;
|
_home.options = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// a relative ground position to home in meters, Down
|
||||||
|
void AP_AHRS_DCM::get_relative_position_D_home(float &posD) const
|
||||||
|
{
|
||||||
|
posD = -_baro.get_altitude();
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
check if the AHRS subsystem is healthy
|
check if the AHRS subsystem is healthy
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -100,6 +100,8 @@ public:
|
||||||
return _wind;
|
return _wind;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void get_relative_position_D_home(float &posD) const override;
|
||||||
|
|
||||||
// return an airspeed estimate if available. return true
|
// return an airspeed estimate if available. return true
|
||||||
// if we have an estimate
|
// if we have an estimate
|
||||||
bool airspeed_estimate(float *airspeed_ret) const;
|
bool airspeed_estimate(float *airspeed_ret) const;
|
||||||
|
|
Loading…
Reference in New Issue