AP_AHRS: implement get_vibration method on AHRS

This commit is contained in:
Andrew Tridgell 2020-03-06 21:11:25 +11:00
parent 9f92aad711
commit 393a8785f3
2 changed files with 9 additions and 0 deletions

View File

@ -518,6 +518,12 @@ void AP_AHRS::update_nmea_out()
#endif
}
// return current vibration vector for primary IMU
Vector3f AP_AHRS::get_vibration(void) const
{
return AP::ins().get_vibration_levels();
}
// singleton instance
AP_AHRS *AP_AHRS::_singleton;

View File

@ -550,6 +550,9 @@ public:
// Write position and quaternion data from an external navigation system
virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) { }
// return current vibration vector for primary IMU
Vector3f get_vibration(void) const;
// allow threads to lock against AHRS update
HAL_Semaphore &get_semaphore(void) {
return _rsem;