InertionSensor: update for new Ch6() interface

This commit is contained in:
Andrew Tridgell 2012-03-07 15:15:45 +11:00
parent d1976449fd
commit ff4f7ccc65
2 changed files with 5 additions and 5 deletions

View File

@ -55,7 +55,7 @@ void AP_InertialSensor_Oilpan::init( AP_PeriodicProcess * scheduler)
bool AP_InertialSensor_Oilpan::update()
{
uint16_t adc_values[6];
float adc_values[6];
_sample_time = _adc->Ch6(_sensors, adc_values);
_temp = _adc->Ch(_gyro_temp_ch);
@ -115,13 +115,13 @@ void AP_InertialSensor_Oilpan::reset_sample_time() { }
/* ------ Private functions -------------------------------------------*/
float AP_InertialSensor_Oilpan::_gyro_apply_std_offset( uint16_t adc_value )
float AP_InertialSensor_Oilpan::_gyro_apply_std_offset( float adc_value )
{
/* Magic number from AP_ADC_Oilpan.h */
return ((float) adc_value ) - 1658.0f;
}
float AP_InertialSensor_Oilpan::_accel_apply_std_offset( uint16_t adc_value )
float AP_InertialSensor_Oilpan::_accel_apply_std_offset( float adc_value )
{
/* Magic number from AP_ADC_Oilpan.h */
return ((float) adc_value ) - 2041.0f;

View File

@ -55,8 +55,8 @@ class AP_InertialSensor_Oilpan : public AP_InertialSensor
static const float _adc_constraint;
float _gyro_apply_std_offset( uint16_t adc_value );
float _accel_apply_std_offset( uint16_t adc_value );
float _gyro_apply_std_offset( float adc_value );
float _accel_apply_std_offset( float adc_value );
};
#endif // __AP_INERTIAL_SENSOR_OILPAN_H__