From e6e161d56dc34c9595b10ec24b5549feb800c494 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sat, 19 Feb 2011 03:57:19 +0000 Subject: [PATCH] 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 --- libraries/AP_IMU/AP_IMU_Oilpan.cpp | 6 ++++++ libraries/AP_IMU/AP_IMU_Oilpan.h | 13 ++++++++++++- 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/libraries/AP_IMU/AP_IMU_Oilpan.cpp b/libraries/AP_IMU/AP_IMU_Oilpan.cpp index 819662756c..a635d28397 100644 --- a/libraries/AP_IMU/AP_IMU_Oilpan.cpp +++ b/libraries/AP_IMU/AP_IMU_Oilpan.cpp @@ -123,6 +123,12 @@ AP_IMU_Oilpan::_init_gyro() } } +void +AP_IMU_Oilpan::save() +{ + _sensor_cal.save(); +} + void AP_IMU_Oilpan::init_accel() { diff --git a/libraries/AP_IMU/AP_IMU_Oilpan.h b/libraries/AP_IMU/AP_IMU_Oilpan.h index 6865022889..1678c61ce9 100644 --- a/libraries/AP_IMU/AP_IMU_Oilpan.h +++ b/libraries/AP_IMU/AP_IMU_Oilpan.h @@ -41,11 +41,22 @@ public: /// WARM_START loads accelerometer and gyro calibration from a previous cold start. /// 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 _sensor_cal; ///< Calibrated sensor offsets