mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_IMU/AP_IMU_INS.h
This commit is contained in:
parent
4aa6f1d7a3
commit
37fd49d8de
|
@ -45,7 +45,7 @@ public:
|
|||
virtual void init( Start_style style = COLD_START,
|
||||
void (*delay_cb)(unsigned long t) = delay,
|
||||
void (*flash_leds_cb)(bool on) = NULL,
|
||||
AP_PeriodicProcess *scheduler = NULL );
|
||||
AP_PeriodicProcess * scheduler = NULL );
|
||||
|
||||
virtual void save();
|
||||
virtual void init_accel(void (*delay_cb)(unsigned long t) = delay,
|
||||
|
@ -56,24 +56,48 @@ 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);
|
||||
|
||||
|
||||
private:
|
||||
AP_InertialSensor *_ins; ///< INS provides an axis and unit correct sensor source.
|
||||
AP_InertialSensor * _ins; ///< INS provides an axis and unit correct sensor source.
|
||||
|
||||
virtual void _init_accel(void (*delay_cb)(unsigned long t),
|
||||
void (*flash_leds_cb)(bool on) = NULL); ///< no-save implementation
|
||||
|
|
Loading…
Reference in New Issue