Correct file references for repository

git-svn-id: https://arducopter.googlecode.com/svn/trunk@727 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
deweibel 2010-10-24 19:12:09 +00:00
parent 489365e7fc
commit de51162e81
3 changed files with 5 additions and 5 deletions

View File

@ -1,5 +1,5 @@
#include "AP_DCM_FW.h"
#include <AP_DCM_FW.h>
#define OUTPUTMODE 1 // This is just used for debugging, remove later

View File

@ -8,7 +8,7 @@
#include <APM_Compass.h>
#include <APM_ADC.h>
#include <AP_GPS.h>
#include "AP_IMU.h"
#include <AP_IMU.h>
class AP_DCM_FW

View File

@ -1,5 +1,5 @@
#include "AP_IMU.h"
#include <AP_IMU.h>
#define A_LED_PIN 37 //37 = A, 35 = C
#define C_LED_PIN 35
@ -82,7 +82,7 @@ AP_IMU::init(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] -= _gyro_temp_comp(j, tc_temp); // Subtract temp compensated typical gyro bias
_adc_in[j] -= _gyro_temp_curve(j, tc_temp); // Subtract temp compensated typical gyro bias
if (_sensor_signs[j] < 0)
temp = (_adc_offset[j] - _adc_in[j]);
else
@ -119,7 +119,7 @@ AP_IMU::get_gyro(void)
for (int i = 0; i < 3; i++) {
_adc_in[i] = APM_ADC.Ch(_sensors[i]);
_adc_in[i] -= _gyro_temp_comp(i, tc_temp); // Subtract temp compensated typical gyro bias
_adc_in[i] -= _gyro_temp_curve(i, tc_temp); // Subtract temp compensated typical gyro bias
if (_sensor_signs[i] < 0)
temp = (_adc_offset[i] - _adc_in[i]);
else