mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
uncrustify libraries/AP_IMU/AP_IMU_INS.h
This commit is contained in:
parent
4aa6f1d7a3
commit
37fd49d8de
@ -56,19 +56,43 @@ public:
|
||||
virtual bool new_data_available(void);
|
||||
|
||||
// for jason
|
||||
virtual float gx() { return _sensor_cal[0]; }
|
||||
virtual float gy() { return _sensor_cal[1]; }
|
||||
virtual float gz() { return _sensor_cal[2]; }
|
||||
virtual float ax() { return _sensor_cal[3]; }
|
||||
virtual float ay() { return _sensor_cal[4]; }
|
||||
virtual float az() { return _sensor_cal[5]; }
|
||||
virtual float gx() {
|
||||
return _sensor_cal[0];
|
||||
}
|
||||
virtual float gy() {
|
||||
return _sensor_cal[1];
|
||||
}
|
||||
virtual float gz() {
|
||||
return _sensor_cal[2];
|
||||
}
|
||||
virtual float ax() {
|
||||
return _sensor_cal[3];
|
||||
}
|
||||
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; }
|
||||
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;
|
||||
}
|
||||
virtual float get_gyro_drift_rate(void);
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user