ardupilot/libraries/AP_ADC/AP_ADC_HIL.cpp
james.goppert 40f1d184a1 Cleaned up AP_ADC_HIL
git-svn-id: https://arducopter.googlecode.com/svn/trunk@961 f9c3cf11-9bcb-44bc-f272-b75c42450872
2010-11-28 00:28:01 +00:00

57 lines
1.4 KiB
C++

#include "AP_ADC_HIL.h"
#include "WProgram.h"
/*
AP_ADC_HIL.cpp
Author: James Goppert
License:
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
*/
const uint8_t AP_ADC_HIL::sensors[6] = {1,2,0,4,5,6};
const int8_t AP_ADC_HIL::sensorSign[6] = { 1, -1, -1,-1, 1, 1};
const float AP_ADC_HIL::gyroBias[3] = {1665,1665,1665};
const float AP_ADC_HIL::accelBias[3] = {2025,2025,2025};
// gyroScale = 1/[GyroGain*pi/180] GyroGains (0.4,0.41,0.41)
const float AP_ADC_HIL::gyroScale[3] = {142.239, 139.746, 139.746};
const float AP_ADC_HIL::accelScale[3] = {418,418,418}; // adcPerG
AP_ADC_HIL::AP_ADC_HIL() : adcValue()
{
}
void AP_ADC_HIL::Init(void)
{
}
// Read one channel value
int AP_ADC_HIL::Ch(unsigned char ch_num)
{
return adcValue[ch_num];
}
// Set one channel value
int AP_ADC_HIL::setHIL(int16_t p, int16_t q, int16_t r, int16_t gyroTemp,
int16_t aX, int16_t aY, int16_t aZ, int16_t diffPress)
{
// gyros
setGyro(0,p);
setGyro(1,q);
setGyro(2,r);
// temp
setGyroTemp(gyroTemp);
// accel
setAccel(0,aX);
setAccel(0,aY);
setAccel(0,aZ);
// differential pressure
setPressure(diffPress);
}