AP_ADC: ADS1115: coding style fixes
- Clean trailing whitespaces - Fix switch - Use pragma once
This commit is contained in:
parent
c1d19fa4dc
commit
4562c0cffc
@ -88,15 +88,14 @@
|
||||
#define error(fmt, args ...)
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
#define ADS1115_CHANNELS_COUNT 6
|
||||
|
||||
const uint8_t AP_ADC_ADS1115::_channels_number = ADS1115_CHANNELS_COUNT;
|
||||
|
||||
/* Only two differential channels used */
|
||||
static const uint16_t mux_table[ADS1115_CHANNELS_COUNT] =
|
||||
{
|
||||
static const uint16_t mux_table[ADS1115_CHANNELS_COUNT] = {
|
||||
ADS1115_MUX_P1_N3,
|
||||
ADS1115_MUX_P2_N3,
|
||||
ADS1115_MUX_P0_NG,
|
||||
@ -161,35 +160,35 @@ float AP_ADC_ADS1115::_convert_register_data_to_mv(int16_t word) const
|
||||
float pga;
|
||||
|
||||
switch (_gain) {
|
||||
case ADS1115_PGA_6P144:
|
||||
pga = ADS1115_MV_6P144;
|
||||
break;
|
||||
case ADS1115_PGA_4P096:
|
||||
pga = ADS1115_MV_4P096;
|
||||
break;
|
||||
case ADS1115_PGA_2P048:
|
||||
pga = ADS1115_MV_2P048;
|
||||
break;
|
||||
case ADS1115_PGA_1P024:
|
||||
pga = ADS1115_MV_1P024;
|
||||
break;
|
||||
case ADS1115_PGA_0P512:
|
||||
pga = ADS1115_MV_0P512;
|
||||
break;
|
||||
case ADS1115_PGA_0P256:
|
||||
pga = ADS1115_MV_0P256;
|
||||
break;
|
||||
case ADS1115_PGA_0P256B:
|
||||
pga = ADS1115_MV_0P256B;
|
||||
break;
|
||||
case ADS1115_PGA_0P256C:
|
||||
pga = ADS1115_MV_0P256C;
|
||||
break;
|
||||
default:
|
||||
pga = 0.0f;
|
||||
hal.console->printf("Wrong gain");
|
||||
AP_HAL::panic("ADS1115: wrong gain selected");
|
||||
break;
|
||||
case ADS1115_PGA_6P144:
|
||||
pga = ADS1115_MV_6P144;
|
||||
break;
|
||||
case ADS1115_PGA_4P096:
|
||||
pga = ADS1115_MV_4P096;
|
||||
break;
|
||||
case ADS1115_PGA_2P048:
|
||||
pga = ADS1115_MV_2P048;
|
||||
break;
|
||||
case ADS1115_PGA_1P024:
|
||||
pga = ADS1115_MV_1P024;
|
||||
break;
|
||||
case ADS1115_PGA_0P512:
|
||||
pga = ADS1115_MV_0P512;
|
||||
break;
|
||||
case ADS1115_PGA_0P256:
|
||||
pga = ADS1115_MV_0P256;
|
||||
break;
|
||||
case ADS1115_PGA_0P256B:
|
||||
pga = ADS1115_MV_0P256B;
|
||||
break;
|
||||
case ADS1115_PGA_0P256C:
|
||||
pga = ADS1115_MV_0P256C;
|
||||
break;
|
||||
default:
|
||||
pga = 0.0f;
|
||||
hal.console->printf("Wrong gain");
|
||||
AP_HAL::panic("ADS1115: wrong gain selected");
|
||||
break;
|
||||
}
|
||||
|
||||
return (float) word * pga;
|
||||
|
@ -1,7 +1,5 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#ifndef __AP_ADC_ADS1115_H__
|
||||
#define __AP_ADC_ADS1115_H__
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "AP_ADC.h"
|
||||
@ -43,5 +41,3 @@ private:
|
||||
|
||||
float _convert_register_data_to_mv(int16_t word) const;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user