AP_IMU modified to use AP_ADC, fixes HIL bugs.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@949 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-11-27 04:45:29 +00:00
parent da9ecf342c
commit a6c315b6f1
2 changed files with 12 additions and 13 deletions

View File

@ -1,5 +1,5 @@
/*
APM_IMU.cpp - IMU Sensor Library for Ardupilot Mega
AP_IMU.cpp - IMU Sensor Library for Ardupilot Mega
Code by Doug Weibel, Jordi Muñoz and Jose Julio. DIYDrones.com
This library works with the ArduPilot Mega and "Oilpan"
@ -54,12 +54,10 @@ const float AP_IMU::_gyro_temp_curve[3][3] = {
{1665,0,0}
}; // To Do - make additional constructors to pass this in.
// Someone is responsible for providing an APM_ADC instance.
extern APM_ADC_Class APM_ADC;
// Constructors ////////////////////////////////////////////////////////////////
AP_IMU::AP_IMU(void)
AP_IMU::AP_IMU(AP_ADC * adc)
: _adc(adc)
{
}
@ -81,7 +79,7 @@ AP_IMU::read_offsets(void)
float temp;
int flashcount = 0;
int tc_temp = APM_ADC.Ch(_gyro_temp_ch);
int tc_temp = _adc->Ch(_gyro_temp_ch);
delay(500);
for(int c = 0; c < 200; c++)
@ -90,7 +88,7 @@ AP_IMU::read_offsets(void)
digitalWrite(C_LED_PIN, HIGH);
delay(20);
for (int i = 0; i < 6; i++)
_adc_in[i] = APM_ADC.Ch(_sensors[i]);
_adc_in[i] = _adc->Ch(_sensors[i]);
digitalWrite(C_LED_PIN, LOW);
digitalWrite(A_LED_PIN, HIGH);
delay(20);
@ -98,7 +96,7 @@ AP_IMU::read_offsets(void)
for(int i = 0; i < 200; i++){ // We take some readings...
for (int j = 0; j < 6; j++) {
_adc_in[j] = APM_ADC.Ch(_sensors[j]);
_adc_in[j] = _adc->Ch(_sensors[j]);
if (j < 3) {
_adc_in[j] -= gyro_temp_comp(j, tc_temp); // Subtract temp compensated typical gyro bias
} else {
@ -171,10 +169,10 @@ AP_IMU::gyro_temp_comp(int i, int temp) const
Vector3f
AP_IMU::get_gyro(void)
{
int tc_temp = APM_ADC.Ch(_gyro_temp_ch);
int tc_temp = _adc->Ch(_gyro_temp_ch);
for (int i = 0; i < 3; i++) {
_adc_in[i] = APM_ADC.Ch(_sensors[i]);
_adc_in[i] = _adc->Ch(_sensors[i]);
_adc_in[i] -= gyro_temp_comp(i,tc_temp); // Subtract temp compensated typical gyro bias
if (_sensor_signs[i] < 0)
_adc_in[i] = (_adc_offset[i] - _adc_in[i]);
@ -199,7 +197,7 @@ Vector3f
AP_IMU::get_accel(void)
{
for (int i = 3; i < 6; i++) {
_adc_in[i] = APM_ADC.Ch(_sensors[i]);
_adc_in[i] = _adc->Ch(_sensors[i]);
_adc_in[i] -= 2025; // Subtract typical accel bias
if (_sensor_signs[i] < 0)
_adc_in[i] = (_adc_offset[i] - _adc_in[i]);

View File

@ -5,7 +5,7 @@
#include <AP_Math.h>
#include <inttypes.h>
#include "WProgram.h"
#include <APM_ADC.h>
#include <AP_ADC.h>
#include <avr/eeprom.h>
@ -13,7 +13,7 @@ class AP_IMU
{
public:
// Constructors
AP_IMU(); // Default Constructor
AP_IMU(AP_ADC * adc); // Default Constructor
// Methods
void quick_init(uint16_t *_offset_address); // For air start
@ -37,6 +37,7 @@ private:
float _adc_offset[6]; // Array that store the Offset of the gyros and accelerometers
Vector3f _accel_vector; // Store the acceleration in a vector
Vector3f _gyro_vector; // Store the gyros turn rate in a vector
AP_ADC * _adc; // Analog to digital converter pointer
// constants
static const uint8_t _sensors[6];