mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_IMU_INS: added gx(), gy() and gz() methods to return gyro offsets
This commit is contained in:
parent
dfea845c37
commit
ae119b08b3
@ -63,6 +63,9 @@ public:
|
||||
virtual float ay() { return _sensor_cal[4]; }
|
||||
virtual float az() { return _sensor_cal[5]; }
|
||||
|
||||
virtual void gx(const float v) { _sensor_cal[0] = v; }
|
||||
virtual void gy(const float v) { _sensor_cal[1] = v; }
|
||||
virtual void gz(const float v) { _sensor_cal[2] = v; }
|
||||
virtual void ax(const float v) { _sensor_cal[3] = v; }
|
||||
virtual void ay(const float v) { _sensor_cal[4] = v; }
|
||||
virtual void az(const float v) { _sensor_cal[5] = v; }
|
||||
|
Loading…
Reference in New Issue
Block a user