2012-10-09 19:39:43 -03:00
|
|
|
|
2011-09-18 00:49:00 -03:00
|
|
|
#include "AP_ADC_HIL.h"
|
2012-10-09 19:39:43 -03:00
|
|
|
#include <AP_HAL.h>
|
|
|
|
extern const AP_HAL::HAL& hal;
|
2013-08-26 06:36:56 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
2011-09-18 00:49:00 -03:00
|
|
|
|
2013-08-26 06:36:56 -03:00
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
2011-09-18 00:49:00 -03:00
|
|
|
/*
|
2012-08-17 02:39:21 -03:00
|
|
|
* AP_ADC_HIL.cpp
|
|
|
|
* Author: James Goppert
|
|
|
|
*
|
|
|
|
*/
|
2011-09-18 00:49:00 -03:00
|
|
|
|
|
|
|
const uint8_t AP_ADC_HIL::sensors[6] = {1,2,0,4,5,6};
|
2012-08-17 02:39:21 -03:00
|
|
|
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};
|
2011-09-18 00:49:00 -03:00
|
|
|
// gyroScale = 1/[GyroGain*pi/180] GyroGains (0.4,0.41,0.41)
|
|
|
|
const float AP_ADC_HIL::gyroScale[3] = {143.239, 139.746, 139.746};
|
|
|
|
const float AP_ADC_HIL::accelScale[3] = {418,418,418}; // adcPerG
|
2012-11-26 06:53:51 -04:00
|
|
|
|
2011-09-18 00:49:00 -03:00
|
|
|
AP_ADC_HIL::AP_ADC_HIL()
|
|
|
|
{
|
2012-08-17 02:39:21 -03:00
|
|
|
// gyros set to zero for calibration
|
|
|
|
setGyro(0,0);
|
|
|
|
setGyro(1,0);
|
|
|
|
setGyro(2,0);
|
2011-09-18 00:49:00 -03:00
|
|
|
|
2012-08-17 02:39:21 -03:00
|
|
|
// accels set to zero for calibration
|
|
|
|
setAccel(0,0);
|
|
|
|
setAccel(1,0);
|
|
|
|
setAccel(2,0);
|
2011-09-18 00:49:00 -03:00
|
|
|
|
2012-08-17 02:39:21 -03:00
|
|
|
// set diff press and temp to zero
|
|
|
|
setGyroTemp(0);
|
|
|
|
setPressure(0);
|
2011-09-18 00:49:00 -03:00
|
|
|
}
|
|
|
|
|
2012-10-09 19:39:43 -03:00
|
|
|
void AP_ADC_HIL::Init()
|
2011-09-18 00:49:00 -03:00
|
|
|
{
|
2013-09-28 03:30:16 -03:00
|
|
|
hal.scheduler->register_timer_process( reinterpret_cast<AP_HAL::TimedProc>(&AP_ADC_HIL::read), this);
|
2011-09-18 00:49:00 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// Read one channel value
|
2011-12-10 06:43:57 -04:00
|
|
|
float AP_ADC_HIL::Ch(unsigned char ch_num)
|
2011-09-18 00:49:00 -03:00
|
|
|
{
|
2012-08-17 02:39:21 -03:00
|
|
|
return adcValue[ch_num];
|
2011-09-15 05:45:51 -03:00
|
|
|
}
|
2011-09-15 00:01:45 -03:00
|
|
|
|
|
|
|
// Read 6 channel values
|
2012-03-07 00:14:29 -04:00
|
|
|
uint32_t AP_ADC_HIL::Ch6(const uint8_t *channel_numbers, float *result)
|
2011-09-15 05:45:51 -03:00
|
|
|
{
|
2012-11-26 06:53:51 -04:00
|
|
|
_count = 0;
|
|
|
|
|
2012-08-17 02:39:21 -03:00
|
|
|
for (uint8_t i=0; i<6; i++) {
|
|
|
|
result[i] = Ch(channel_numbers[i]);
|
|
|
|
}
|
2013-04-01 23:20:08 -03:00
|
|
|
uint32_t now = hal.scheduler->micros();
|
|
|
|
uint32_t ret = now - _last_ch6_time;
|
|
|
|
_last_ch6_time = now;
|
|
|
|
return ret;
|
2011-09-18 00:49:00 -03:00
|
|
|
}
|
|
|
|
|
2012-03-03 03:31:09 -04:00
|
|
|
// see if new data is available
|
|
|
|
bool AP_ADC_HIL::new_data_available(const uint8_t *channel_numbers)
|
|
|
|
{
|
2012-08-17 02:39:21 -03:00
|
|
|
return true;
|
2012-03-03 03:31:09 -04:00
|
|
|
}
|
2012-08-30 04:50:03 -03:00
|
|
|
|
|
|
|
// Get minimum number of samples read from the sensors
|
|
|
|
uint16_t AP_ADC_HIL::num_samples_available(const uint8_t *channel_numbers)
|
|
|
|
{
|
2012-11-26 06:53:51 -04:00
|
|
|
return _count;
|
2012-10-09 19:39:43 -03:00
|
|
|
}
|