Browse Source

AP_HAL_Linux: AnalogIn_Raspilot: rename classes to follow other names

mission-4.1.18
Lucas De Marchi 9 years ago
parent
commit
21b2d5d34c
  1. 12
      libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp
  2. 6
      libraries/AP_HAL_Linux/AnalogIn_Raspilot.h
  3. 2
      libraries/AP_HAL_Linux/HAL_Linux_Class.cpp

12
libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp

@ -46,12 +46,12 @@ float AnalogSource_Raspilot::voltage_average_ratiometric()
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
RaspilotAnalogIn::RaspilotAnalogIn() AnalogIn_Raspilot::AnalogIn_Raspilot()
{ {
_channels_number = RASPILOT_ADC_MAX_CHANNELS; _channels_number = RASPILOT_ADC_MAX_CHANNELS;
} }
float RaspilotAnalogIn::board_voltage(void) float AnalogIn_Raspilot::board_voltage(void)
{ {
_vcc_pin_analog_source->set_pin(4); _vcc_pin_analog_source->set_pin(4);
@ -59,7 +59,7 @@ float RaspilotAnalogIn::board_voltage(void)
//return _vcc_pin_analog_source->voltage_average() * 2.0; //return _vcc_pin_analog_source->voltage_average() * 2.0;
} }
AP_HAL::AnalogSource* RaspilotAnalogIn::channel(int16_t pin) AP_HAL::AnalogSource* AnalogIn_Raspilot::channel(int16_t pin)
{ {
for (uint8_t j = 0; j < _channels_number; j++) { for (uint8_t j = 0; j < _channels_number; j++) {
if (_channels[j] == NULL) { if (_channels[j] == NULL) {
@ -72,7 +72,7 @@ AP_HAL::AnalogSource* RaspilotAnalogIn::channel(int16_t pin)
return NULL; return NULL;
} }
void RaspilotAnalogIn::init() void AnalogIn_Raspilot::init()
{ {
_vcc_pin_analog_source = channel(4); _vcc_pin_analog_source = channel(4);
@ -86,11 +86,11 @@ void RaspilotAnalogIn::init()
} }
hal.scheduler->suspend_timer_procs(); hal.scheduler->suspend_timer_procs();
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&RaspilotAnalogIn::_update, void)); hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AnalogIn_Raspilot::_update, void));
hal.scheduler->resume_timer_procs(); hal.scheduler->resume_timer_procs();
} }
void RaspilotAnalogIn::_update() void AnalogIn_Raspilot::_update()
{ {
if (AP_HAL::micros() - _last_update_timestamp < 100000) { if (AP_HAL::micros() - _last_update_timestamp < 100000) {
return; return;

6
libraries/AP_HAL_Linux/AnalogIn_Raspilot.h

@ -8,7 +8,7 @@
class AnalogSource_Raspilot: public AP_HAL::AnalogSource { class AnalogSource_Raspilot: public AP_HAL::AnalogSource {
public: public:
friend class RaspilotAnalogIn; friend class AnalogIn_Raspilot;
AnalogSource_Raspilot(int16_t pin); AnalogSource_Raspilot(int16_t pin);
float read_average(); float read_average();
float read_latest(); float read_latest();
@ -23,9 +23,9 @@ private:
float _value; float _value;
}; };
class RaspilotAnalogIn: public AP_HAL::AnalogIn { class AnalogIn_Raspilot: public AP_HAL::AnalogIn {
public: public:
RaspilotAnalogIn(); AnalogIn_Raspilot();
void init(); void init();
AP_HAL::AnalogSource* channel(int16_t n); AP_HAL::AnalogSource* channel(int16_t n);

2
libraries/AP_HAL_Linux/HAL_Linux_Class.cpp

@ -79,7 +79,7 @@ static SPIDeviceManager spiDeviceManager;
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
static AnalogIn_ADS1115 analogIn; static AnalogIn_ADS1115 analogIn;
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
static RaspilotAnalogIn analogIn; static AnalogIn_Raspilot analogIn;
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
static Empty::AnalogIn analogIn; static Empty::AnalogIn analogIn;
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \ #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \

Loading…
Cancel
Save