mirror of https://github.com/ArduPilot/ardupilot
IMU: move _sensor_cal to general IMU class
this makes it available both in shim and INS subclasses
This commit is contained in:
parent
2b8f0c3a48
commit
371a91cfcf
|
@ -21,11 +21,6 @@
|
|||
|
||||
#include "AP_IMU_INS.h"
|
||||
|
||||
const AP_Param::GroupInfo AP_IMU_INS::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("CAL", 0, AP_IMU_INS, _sensor_cal),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
void
|
||||
AP_IMU_INS::init( Start_style style,
|
||||
void (*delay_cb)(unsigned long t),
|
||||
|
|
|
@ -64,11 +64,8 @@ public:
|
|||
virtual void ay(const float v) { _sensor_cal[4] = v; }
|
||||
virtual void az(const float v) { _sensor_cal[5] = v; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AP_InertialSensor *_ins; ///< INS provides an axis and unit correct sensor source.
|
||||
AP_Vector6f _sensor_cal; ///< Calibrated sensor offsets
|
||||
|
||||
virtual void _init_accel(void (*delay_cb)(unsigned long t),
|
||||
void (*flash_leds_cb)(bool on) = NULL); ///< no-save implementation
|
||||
|
|
|
@ -1,6 +1,13 @@
|
|||
|
||||
#include "IMU.h"
|
||||
|
||||
// this allows the sensor calibration to be saved to EEPROM
|
||||
const AP_Param::GroupInfo IMU::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("CAL", 0, IMU, _sensor_cal),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
||||
/* Empty implementations for the IMU functions.
|
||||
* Although these will never be used, in certain situations with
|
||||
* optimizations turned off, having empty implementations in an object
|
||||
|
|
|
@ -104,7 +104,12 @@ public:
|
|||
virtual void ay(const float v);
|
||||
virtual void az(const float v);
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
protected:
|
||||
|
||||
AP_Vector6f _sensor_cal; ///< Calibrated sensor offsets
|
||||
|
||||
/// Most recent accelerometer reading obtained by ::update
|
||||
Vector3f _accel;
|
||||
Vector3f _accel_filtered;
|
||||
|
|
Loading…
Reference in New Issue