Added accessors back for Accels. I need them there until we need to find another solution.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1676 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-02-19 03:57:19 +00:00
parent da4cff5440
commit e6e161d56d
2 changed files with 18 additions and 1 deletions

View File

@ -123,6 +123,12 @@ AP_IMU_Oilpan::_init_gyro()
}
}
void
AP_IMU_Oilpan::save()
{
_sensor_cal.save();
}
void
AP_IMU_Oilpan::init_accel()
{

View File

@ -42,10 +42,21 @@ public:
///
virtual void init(Start_style style = COLD_START);
virtual void save();
virtual void init_accel();
virtual void init_gyro();
virtual bool update(void);
// for jason
int ax() { return _sensor_cal[3]; }
int ay() { return _sensor_cal[4]; }
int az() { return _sensor_cal[5]; }
void ax(const int v) { _sensor_cal[3] = v; }
void ay(const int v) { _sensor_cal[4] = v; }
void az(const int v) { _sensor_cal[5] = v; }
private:
AP_ADC *_adc; ///< ADC that we use for reading sensors
AP_VarA<float,6> _sensor_cal; ///< Calibrated sensor offsets