Browse Source

AP_AHRS: added get_accel() for lua access

c415-sdk
Andrew Tridgell 5 years ago committed by WickedShell
parent
commit
3f69f97d60
  1. 5
      libraries/AP_AHRS/AP_AHRS.h

5
libraries/AP_AHRS/AP_AHRS.h

@ -210,6 +210,11 @@ public:
// return a smoothed and corrected gyro vector in radians/second // return a smoothed and corrected gyro vector in radians/second
virtual const Vector3f &get_gyro(void) const = 0; 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) // 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; Vector3f get_gyro_latest(void) const;

Loading…
Cancel
Save