You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
140 lines
3.3 KiB
140 lines
3.3 KiB
10 years ago
|
#include <AP_HAL/AP_HAL.h>
|
||
|
|
||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||
|
|
||
9 years ago
|
#include "AnalogIn_Raspilot.h"
|
||
10 years ago
|
#include "px4io_protocol.h"
|
||
|
|
||
9 years ago
|
AnalogSource_Raspilot::AnalogSource_Raspilot(int16_t pin):
|
||
10 years ago
|
_pin(pin),
|
||
|
_value(0.0f)
|
||
|
{
|
||
|
}
|
||
|
|
||
9 years ago
|
void AnalogSource_Raspilot::set_pin(uint8_t pin)
|
||
10 years ago
|
{
|
||
|
if (_pin == pin) {
|
||
|
return;
|
||
|
}
|
||
|
_pin = pin;
|
||
|
}
|
||
|
|
||
9 years ago
|
float AnalogSource_Raspilot::read_average()
|
||
|
{
|
||
10 years ago
|
return read_latest();
|
||
|
}
|
||
|
|
||
9 years ago
|
float AnalogSource_Raspilot::read_latest()
|
||
10 years ago
|
{
|
||
|
return _value;
|
||
|
}
|
||
|
|
||
9 years ago
|
float AnalogSource_Raspilot::voltage_average()
|
||
10 years ago
|
{
|
||
|
return _value;
|
||
|
}
|
||
|
|
||
9 years ago
|
float AnalogSource_Raspilot::voltage_latest()
|
||
10 years ago
|
{
|
||
|
return _value;
|
||
|
}
|
||
|
|
||
9 years ago
|
float AnalogSource_Raspilot::voltage_average_ratiometric()
|
||
10 years ago
|
{
|
||
|
return _value;
|
||
|
}
|
||
|
|
||
|
extern const AP_HAL::HAL& hal;
|
||
|
|
||
|
RaspilotAnalogIn::RaspilotAnalogIn()
|
||
|
{
|
||
|
_channels_number = RASPILOT_ADC_MAX_CHANNELS;
|
||
|
}
|
||
|
|
||
|
float RaspilotAnalogIn::board_voltage(void)
|
||
|
{
|
||
|
_vcc_pin_analog_source->set_pin(4);
|
||
9 years ago
|
|
||
10 years ago
|
return 5.0;
|
||
|
//return _vcc_pin_analog_source->voltage_average() * 2.0;
|
||
|
}
|
||
|
|
||
|
AP_HAL::AnalogSource* RaspilotAnalogIn::channel(int16_t pin)
|
||
|
{
|
||
|
for (uint8_t j = 0; j < _channels_number; j++) {
|
||
|
if (_channels[j] == NULL) {
|
||
9 years ago
|
_channels[j] = new AnalogSource_Raspilot(pin);
|
||
10 years ago
|
return _channels[j];
|
||
|
}
|
||
|
}
|
||
|
|
||
|
hal.console->println("Out of analog channels");
|
||
|
return NULL;
|
||
|
}
|
||
|
|
||
9 years ago
|
void RaspilotAnalogIn::init()
|
||
10 years ago
|
{
|
||
|
_vcc_pin_analog_source = channel(4);
|
||
9 years ago
|
|
||
10 years ago
|
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
|
||
|
_spi_sem = _spi->get_semaphore();
|
||
9 years ago
|
|
||
10 years ago
|
if (_spi_sem == NULL) {
|
||
9 years ago
|
AP_HAL::panic("PANIC: RCIutput_Raspilot did not get "
|
||
10 years ago
|
"valid SPI semaphore!");
|
||
10 years ago
|
return; // never reached
|
||
|
}
|
||
9 years ago
|
|
||
10 years ago
|
hal.scheduler->suspend_timer_procs();
|
||
|
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&RaspilotAnalogIn::_update, void));
|
||
|
hal.scheduler->resume_timer_procs();
|
||
|
}
|
||
|
|
||
|
void RaspilotAnalogIn::_update()
|
||
|
{
|
||
9 years ago
|
if (AP_HAL::micros() - _last_update_timestamp < 100000) {
|
||
10 years ago
|
return;
|
||
|
}
|
||
9 years ago
|
|
||
10 years ago
|
if (!_spi_sem->take_nonblocking()) {
|
||
|
return;
|
||
|
}
|
||
9 years ago
|
|
||
10 years ago
|
struct IOPacket _dma_packet_tx, _dma_packet_rx;
|
||
|
uint16_t count = RASPILOT_ADC_MAX_CHANNELS;
|
||
|
_dma_packet_tx.count_code = count | PKT_CODE_READ;
|
||
|
_dma_packet_tx.page = PX4IO_PAGE_RAW_ADC_INPUT;
|
||
|
_dma_packet_tx.offset = 0;
|
||
|
_dma_packet_tx.crc = 0;
|
||
|
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
|
||
|
/* set raspilotio to read reg4 */
|
||
|
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
|
||
9 years ago
|
|
||
10 years ago
|
hal.scheduler->delay_microseconds(200);
|
||
9 years ago
|
|
||
|
count = 0;
|
||
|
_dma_packet_tx.count_code = count | PKT_CODE_READ;
|
||
|
_dma_packet_tx.page = 0;
|
||
|
_dma_packet_tx.offset = 0;
|
||
|
_dma_packet_tx.crc = 0;
|
||
|
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
|
||
10 years ago
|
/* get reg4 data from raspilotio */
|
||
|
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
|
||
9 years ago
|
|
||
10 years ago
|
_spi_sem->give();
|
||
|
|
||
|
for (int16_t i = 0; i < RASPILOT_ADC_MAX_CHANNELS; i++) {
|
||
|
for (int16_t j=0; j < RASPILOT_ADC_MAX_CHANNELS; j++) {
|
||
9 years ago
|
AnalogSource_Raspilot *source = _channels[j];
|
||
10 years ago
|
|
||
|
if (source != NULL && i == source->_pin) {
|
||
|
source->_value = _dma_packet_rx.regs[i] * 3.3 / 4096.0;
|
||
|
}
|
||
|
}
|
||
|
}
|
||
|
|
||
9 years ago
|
_last_update_timestamp = AP_HAL::micros();
|
||
10 years ago
|
}
|
||
|
|
||
|
#endif
|