AP_AHRS: added get_accel() for lua access

This commit is contained in:
Andrew Tridgell 2020-06-10 15:52:51 +10:00 committed by WickedShell
parent adf40ae606
commit 3f69f97d60
1 changed files with 5 additions and 0 deletions

View File

@ -210,6 +210,11 @@ public:
// return a smoothed and corrected gyro vector in radians/second
virtual const Vector3f &get_gyro(void) const = 0;
// return primary accels, for lua
const Vector3f &get_accel(void) const {
return AP::ins().get_accel();
}
// return a smoothed and corrected gyro vector in radians/second using the latest ins data (which may not have been consumed by the EKF yet)
Vector3f get_gyro_latest(void) const;