mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_Linux: rename RaspilotAnalogIn.cpp to AnalogIn_Raspilot.cpp
This commit is contained in:
parent
1fde473afc
commit
60636c1653
@ -13,8 +13,8 @@
|
|||||||
#include "SPIDriver.h"
|
#include "SPIDriver.h"
|
||||||
#include "AnalogIn.h"
|
#include "AnalogIn.h"
|
||||||
#include "AnalogIn_ADS1115.h"
|
#include "AnalogIn_ADS1115.h"
|
||||||
#include "RaspilotAnalogIn.h"
|
|
||||||
#include "AnalogIn_IIO.h"
|
#include "AnalogIn_IIO.h"
|
||||||
|
#include "AnalogIn_Raspilot.h"
|
||||||
#include "Storage.h"
|
#include "Storage.h"
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
#include "RCInput.h"
|
#include "RCInput.h"
|
||||||
@ -27,6 +27,7 @@
|
|||||||
#include "RCOutput_PRU.h"
|
#include "RCOutput_PRU.h"
|
||||||
#include "RCOutput_AioPRU.h"
|
#include "RCOutput_AioPRU.h"
|
||||||
#include "RCOutput_PCA9685.h"
|
#include "RCOutput_PCA9685.h"
|
||||||
|
#include "RCOutput_Raspilot.h"
|
||||||
#include "RCOutput_ZYNQ.h"
|
#include "RCOutput_ZYNQ.h"
|
||||||
#include "RCOutput_Bebop.h"
|
#include "RCOutput_Bebop.h"
|
||||||
#include "RCOutput_Raspilot.h"
|
#include "RCOutput_Raspilot.h"
|
||||||
@ -46,4 +47,3 @@
|
|||||||
#include "Flow_PX4.h"
|
#include "Flow_PX4.h"
|
||||||
|
|
||||||
#endif // __AP_HAL_LINUX_PRIVATE_H__
|
#endif // __AP_HAL_LINUX_PRIVATE_H__
|
||||||
|
|
||||||
|
@ -2,8 +2,7 @@
|
|||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include <stdio.h>
|
#include "AnalogIn_Raspilot.h"
|
||||||
#include "RaspilotAnalogIn.h"
|
|
||||||
#include "px4io_protocol.h"
|
#include "px4io_protocol.h"
|
||||||
|
|
||||||
#define RASPILOT_ANALOGIN_DEBUG 0
|
#define RASPILOT_ANALOGIN_DEBUG 0
|
||||||
@ -12,17 +11,17 @@
|
|||||||
#define debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
#define debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
||||||
#define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
#define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
||||||
#else
|
#else
|
||||||
#define debug(fmt, args ...)
|
#define debug(fmt, args ...)
|
||||||
#define error(fmt, args ...)
|
#define error(fmt, args ...)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
RaspilotAnalogSource::RaspilotAnalogSource(int16_t pin):
|
AnalogSource_Raspilot::AnalogSource_Raspilot(int16_t pin):
|
||||||
_pin(pin),
|
_pin(pin),
|
||||||
_value(0.0f)
|
_value(0.0f)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void RaspilotAnalogSource::set_pin(uint8_t pin)
|
void AnalogSource_Raspilot::set_pin(uint8_t pin)
|
||||||
{
|
{
|
||||||
if (_pin == pin) {
|
if (_pin == pin) {
|
||||||
return;
|
return;
|
||||||
@ -30,27 +29,27 @@ void RaspilotAnalogSource::set_pin(uint8_t pin)
|
|||||||
_pin = pin;
|
_pin = pin;
|
||||||
}
|
}
|
||||||
|
|
||||||
float RaspilotAnalogSource::read_average()
|
float AnalogSource_Raspilot::read_average()
|
||||||
{
|
{
|
||||||
return read_latest();
|
return read_latest();
|
||||||
}
|
}
|
||||||
|
|
||||||
float RaspilotAnalogSource::read_latest()
|
float AnalogSource_Raspilot::read_latest()
|
||||||
{
|
{
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
|
|
||||||
float RaspilotAnalogSource::voltage_average()
|
float AnalogSource_Raspilot::voltage_average()
|
||||||
{
|
{
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
|
|
||||||
float RaspilotAnalogSource::voltage_latest()
|
float AnalogSource_Raspilot::voltage_latest()
|
||||||
{
|
{
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
|
|
||||||
float RaspilotAnalogSource::voltage_average_ratiometric()
|
float AnalogSource_Raspilot::voltage_average_ratiometric()
|
||||||
{
|
{
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
@ -65,7 +64,7 @@ RaspilotAnalogIn::RaspilotAnalogIn()
|
|||||||
float RaspilotAnalogIn::board_voltage(void)
|
float RaspilotAnalogIn::board_voltage(void)
|
||||||
{
|
{
|
||||||
_vcc_pin_analog_source->set_pin(4);
|
_vcc_pin_analog_source->set_pin(4);
|
||||||
|
|
||||||
return 5.0;
|
return 5.0;
|
||||||
//return _vcc_pin_analog_source->voltage_average() * 2.0;
|
//return _vcc_pin_analog_source->voltage_average() * 2.0;
|
||||||
}
|
}
|
||||||
@ -74,7 +73,7 @@ AP_HAL::AnalogSource* RaspilotAnalogIn::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) {
|
||||||
_channels[j] = new RaspilotAnalogSource(pin);
|
_channels[j] = new AnalogSource_Raspilot(pin);
|
||||||
return _channels[j];
|
return _channels[j];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -86,16 +85,16 @@ AP_HAL::AnalogSource* RaspilotAnalogIn::channel(int16_t pin)
|
|||||||
void RaspilotAnalogIn::init()
|
void RaspilotAnalogIn::init()
|
||||||
{
|
{
|
||||||
_vcc_pin_analog_source = channel(4);
|
_vcc_pin_analog_source = channel(4);
|
||||||
|
|
||||||
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
|
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
|
||||||
_spi_sem = _spi->get_semaphore();
|
_spi_sem = _spi->get_semaphore();
|
||||||
|
|
||||||
if (_spi_sem == NULL) {
|
if (_spi_sem == NULL) {
|
||||||
AP_HAL::panic("PANIC: RCIutput_Raspilot did not get "
|
AP_HAL::panic("PANIC: RCIutput_Raspilot did not get "
|
||||||
"valid SPI semaphore!");
|
"valid SPI semaphore!");
|
||||||
return; // never reached
|
return; // never reached
|
||||||
}
|
}
|
||||||
|
|
||||||
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(&RaspilotAnalogIn::_update, void));
|
||||||
hal.scheduler->resume_timer_procs();
|
hal.scheduler->resume_timer_procs();
|
||||||
@ -106,11 +105,11 @@ void RaspilotAnalogIn::_update()
|
|||||||
if (AP_HAL::micros() - _last_update_timestamp < 100000) {
|
if (AP_HAL::micros() - _last_update_timestamp < 100000) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!_spi_sem->take_nonblocking()) {
|
if (!_spi_sem->take_nonblocking()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
struct IOPacket _dma_packet_tx, _dma_packet_rx;
|
struct IOPacket _dma_packet_tx, _dma_packet_rx;
|
||||||
uint16_t count = RASPILOT_ADC_MAX_CHANNELS;
|
uint16_t count = RASPILOT_ADC_MAX_CHANNELS;
|
||||||
_dma_packet_tx.count_code = count | PKT_CODE_READ;
|
_dma_packet_tx.count_code = count | PKT_CODE_READ;
|
||||||
@ -120,17 +119,23 @@ void RaspilotAnalogIn::_update()
|
|||||||
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
|
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
|
||||||
/* set raspilotio to read reg4 */
|
/* set raspilotio to read reg4 */
|
||||||
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
|
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
|
||||||
|
|
||||||
hal.scheduler->delay_microseconds(200);
|
hal.scheduler->delay_microseconds(200);
|
||||||
|
|
||||||
|
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);
|
||||||
/* get reg4 data from raspilotio */
|
/* get reg4 data from raspilotio */
|
||||||
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
|
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
|
||||||
|
|
||||||
_spi_sem->give();
|
_spi_sem->give();
|
||||||
|
|
||||||
for (int16_t i = 0; i < RASPILOT_ADC_MAX_CHANNELS; i++) {
|
for (int16_t i = 0; i < RASPILOT_ADC_MAX_CHANNELS; i++) {
|
||||||
for (int16_t j=0; j < RASPILOT_ADC_MAX_CHANNELS; j++) {
|
for (int16_t j=0; j < RASPILOT_ADC_MAX_CHANNELS; j++) {
|
||||||
RaspilotAnalogSource *source = _channels[j];
|
AnalogSource_Raspilot *source = _channels[j];
|
||||||
|
|
||||||
if (source != NULL && i == source->_pin) {
|
if (source != NULL && i == source->_pin) {
|
||||||
source->_value = _dma_packet_rx.regs[i] * 3.3 / 4096.0;
|
source->_value = _dma_packet_rx.regs[i] * 3.3 / 4096.0;
|
@ -1,15 +1,15 @@
|
|||||||
#ifndef __RaspilotAnalogIn_H__
|
#pragma once
|
||||||
#define __RaspilotAnalogIn_H__
|
|
||||||
|
#include <AP_ADC/AP_ADC.h>
|
||||||
|
|
||||||
#include "AP_HAL_Linux.h"
|
#include "AP_HAL_Linux.h"
|
||||||
#include <AP_ADC/AP_ADC.h>
|
|
||||||
|
|
||||||
#define RASPILOT_ADC_MAX_CHANNELS 8
|
#define RASPILOT_ADC_MAX_CHANNELS 8
|
||||||
|
|
||||||
class RaspilotAnalogSource: public AP_HAL::AnalogSource {
|
class AnalogSource_Raspilot: public AP_HAL::AnalogSource {
|
||||||
public:
|
public:
|
||||||
friend class RaspilotAnalogIn;
|
friend class RaspilotAnalogIn;
|
||||||
RaspilotAnalogSource(int16_t pin);
|
AnalogSource_Raspilot(int16_t pin);
|
||||||
float read_average();
|
float read_average();
|
||||||
float read_latest();
|
float read_latest();
|
||||||
void set_pin(uint8_t p);
|
void set_pin(uint8_t p);
|
||||||
@ -31,15 +31,15 @@ public:
|
|||||||
|
|
||||||
/* Board voltage is not available */
|
/* Board voltage is not available */
|
||||||
float board_voltage(void);
|
float board_voltage(void);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AP_HAL::AnalogSource *_vcc_pin_analog_source;
|
AP_HAL::AnalogSource *_vcc_pin_analog_source;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_HAL::SPIDeviceDriver *_spi;
|
AP_HAL::SPIDeviceDriver *_spi;
|
||||||
AP_HAL::Semaphore *_spi_sem;
|
AP_HAL::Semaphore *_spi_sem;
|
||||||
|
|
||||||
RaspilotAnalogSource *_channels[RASPILOT_ADC_MAX_CHANNELS];
|
AnalogSource_Raspilot *_channels[RASPILOT_ADC_MAX_CHANNELS];
|
||||||
|
|
||||||
uint8_t _channels_number;
|
uint8_t _channels_number;
|
||||||
|
|
||||||
@ -47,5 +47,3 @@ private:
|
|||||||
|
|
||||||
uint32_t _last_update_timestamp;
|
uint32_t _last_update_timestamp;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
|
Loading…
Reference in New Issue
Block a user