Browse Source

AP_HAL_Linux: AnalogIn_Raspilot: use SPIDevice interface

mission-4.1.18
Lucas De Marchi 9 years ago
parent
commit
86ac9bc367
  1. 32
      libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp
  2. 18
      libraries/AP_HAL_Linux/AnalogIn_Raspilot.h

32
libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp

@ -1,11 +1,13 @@ @@ -1,11 +1,13 @@
#include "AnalogIn_Raspilot.h"
#include <algorithm>
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_Raspilot.h"
#include "px4io_protocol.h"
AnalogSource_Raspilot::AnalogSource_Raspilot(int16_t pin):
_pin(pin),
_value(0.0f)
AnalogSource_Raspilot::AnalogSource_Raspilot(int16_t pin)
: _pin(pin)
{
}
@ -54,7 +56,6 @@ float AnalogIn_Raspilot::board_voltage(void) @@ -54,7 +56,6 @@ float AnalogIn_Raspilot::board_voltage(void)
_vcc_pin_analog_source->set_pin(4);
return 5.0;
//return _vcc_pin_analog_source->voltage_average() * 2.0;
}
AP_HAL::AnalogSource* AnalogIn_Raspilot::channel(int16_t pin)
@ -74,13 +75,10 @@ void AnalogIn_Raspilot::init() @@ -74,13 +75,10 @@ void AnalogIn_Raspilot::init()
{
_vcc_pin_analog_source = channel(4);
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
_spi_sem = _spi->get_semaphore();
if (_spi_sem == NULL) {
AP_HAL::panic("PANIC: RCIutput_Raspilot did not get "
"valid SPI semaphore!");
return; // never reached
_dev = std::move(hal.spi->get_device("raspio"));
if (!_dev) {
AP_HAL::panic("Bus for AnalogIn_Raspilot not found");
return;
}
hal.scheduler->suspend_timer_procs();
@ -94,7 +92,7 @@ void AnalogIn_Raspilot::_update() @@ -94,7 +92,7 @@ void AnalogIn_Raspilot::_update()
return;
}
if (!_spi_sem->take_nonblocking()) {
if (!_dev->get_semaphore()->take_nonblocking()) {
return;
}
@ -105,8 +103,9 @@ void AnalogIn_Raspilot::_update() @@ -105,8 +103,9 @@ void AnalogIn_Raspilot::_update()
tx.offset = 0;
tx.crc = 0;
tx.crc = crc_packet(&tx);
/* set raspilotio to read reg4 */
_spi->transaction((uint8_t *)&tx, (uint8_t *)&rx, sizeof(tx));
_dev->transfer((uint8_t *)&tx, sizeof(tx), (uint8_t *)&rx, sizeof(rx));
hal.scheduler->delay_microseconds(200);
@ -116,10 +115,11 @@ void AnalogIn_Raspilot::_update() @@ -116,10 +115,11 @@ void AnalogIn_Raspilot::_update()
tx.offset = 0;
tx.crc = 0;
tx.crc = crc_packet(&tx);
/* get reg4 data from raspilotio */
_spi->transaction((uint8_t *)&tx, (uint8_t *)&rx, sizeof(tx));
_dev->transfer((uint8_t *)&tx, sizeof(tx), (uint8_t *)&rx, sizeof(rx));
_spi_sem->give();
_dev->get_semaphore()->give();
for (int16_t i = 0; i < RASPILOT_ADC_MAX_CHANNELS; i++) {
for (int16_t j=0; j < RASPILOT_ADC_MAX_CHANNELS; j++) {

18
libraries/AP_HAL_Linux/AnalogIn_Raspilot.h

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
#pragma once
#include <AP_ADC/AP_ADC.h>
#include <AP_HAL/SPIDevice.h>
#include "AP_HAL_Linux.h"
@ -13,8 +14,8 @@ public: @@ -13,8 +14,8 @@ public:
float read_average();
float read_latest();
void set_pin(uint8_t p);
void set_stop_pin(uint8_t p) {}
void set_settle_time(uint16_t settle_time_ms){}
void set_stop_pin(uint8_t p) { }
void set_settle_time(uint16_t settle_time_ms) { }
float voltage_average();
float voltage_latest();
float voltage_average_ratiometric();
@ -26,6 +27,7 @@ private: @@ -26,6 +27,7 @@ private:
class AnalogIn_Raspilot: public AP_HAL::AnalogIn {
public:
AnalogIn_Raspilot();
void init();
AP_HAL::AnalogSource* channel(int16_t n);
@ -33,17 +35,13 @@ public: @@ -33,17 +35,13 @@ public:
float board_voltage(void);
protected:
AP_HAL::AnalogSource *_vcc_pin_analog_source;
private:
AP_HAL::SPIDeviceDriver *_spi;
AP_HAL::Semaphore *_spi_sem;
void _update();
AP_HAL::AnalogSource *_vcc_pin_analog_source;
AnalogSource_Raspilot *_channels[RASPILOT_ADC_MAX_CHANNELS];
uint8_t _channels_number;
void _update();
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev;
uint32_t _last_update_timestamp;
uint8_t _channels_number;
};

Loading…
Cancel
Save