mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_AHRS: implement get_vibration method on AHRS
This commit is contained in:
parent
9f92aad711
commit
393a8785f3
@ -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;
|
||||
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user