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 "AnalogIn.h"
|
||||
#include "AnalogIn_ADS1115.h"
|
||||
#include "RaspilotAnalogIn.h"
|
||||
#include "AnalogIn_IIO.h"
|
||||
#include "AnalogIn_Raspilot.h"
|
||||
#include "Storage.h"
|
||||
#include "GPIO.h"
|
||||
#include "RCInput.h"
|
||||
@ -27,6 +27,7 @@
|
||||
#include "RCOutput_PRU.h"
|
||||
#include "RCOutput_AioPRU.h"
|
||||
#include "RCOutput_PCA9685.h"
|
||||
#include "RCOutput_Raspilot.h"
|
||||
#include "RCOutput_ZYNQ.h"
|
||||
#include "RCOutput_Bebop.h"
|
||||
#include "RCOutput_Raspilot.h"
|
||||
@ -46,4 +47,3 @@
|
||||
#include "Flow_PX4.h"
|
||||
|
||||
#endif // __AP_HAL_LINUX_PRIVATE_H__
|
||||
|
||||
|
@ -2,8 +2,7 @@
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include <stdio.h>
|
||||
#include "RaspilotAnalogIn.h"
|
||||
#include "AnalogIn_Raspilot.h"
|
||||
#include "px4io_protocol.h"
|
||||
|
||||
#define RASPILOT_ANALOGIN_DEBUG 0
|
||||
@ -16,13 +15,13 @@
|
||||
#define error(fmt, args ...)
|
||||
#endif
|
||||
|
||||
RaspilotAnalogSource::RaspilotAnalogSource(int16_t pin):
|
||||
AnalogSource_Raspilot::AnalogSource_Raspilot(int16_t pin):
|
||||
_pin(pin),
|
||||
_value(0.0f)
|
||||
{
|
||||
}
|
||||
|
||||
void RaspilotAnalogSource::set_pin(uint8_t pin)
|
||||
void AnalogSource_Raspilot::set_pin(uint8_t pin)
|
||||
{
|
||||
if (_pin == pin) {
|
||||
return;
|
||||
@ -30,27 +29,27 @@ void RaspilotAnalogSource::set_pin(uint8_t pin)
|
||||
_pin = pin;
|
||||
}
|
||||
|
||||
float RaspilotAnalogSource::read_average()
|
||||
float AnalogSource_Raspilot::read_average()
|
||||
{
|
||||
return read_latest();
|
||||
}
|
||||
|
||||
float RaspilotAnalogSource::read_latest()
|
||||
float AnalogSource_Raspilot::read_latest()
|
||||
{
|
||||
return _value;
|
||||
}
|
||||
|
||||
float RaspilotAnalogSource::voltage_average()
|
||||
float AnalogSource_Raspilot::voltage_average()
|
||||
{
|
||||
return _value;
|
||||
}
|
||||
|
||||
float RaspilotAnalogSource::voltage_latest()
|
||||
float AnalogSource_Raspilot::voltage_latest()
|
||||
{
|
||||
return _value;
|
||||
}
|
||||
|
||||
float RaspilotAnalogSource::voltage_average_ratiometric()
|
||||
float AnalogSource_Raspilot::voltage_average_ratiometric()
|
||||
{
|
||||
return _value;
|
||||
}
|
||||
@ -74,7 +73,7 @@ AP_HAL::AnalogSource* RaspilotAnalogIn::channel(int16_t pin)
|
||||
{
|
||||
for (uint8_t j = 0; j < _channels_number; j++) {
|
||||
if (_channels[j] == NULL) {
|
||||
_channels[j] = new RaspilotAnalogSource(pin);
|
||||
_channels[j] = new AnalogSource_Raspilot(pin);
|
||||
return _channels[j];
|
||||
}
|
||||
}
|
||||
@ -123,6 +122,12 @@ void RaspilotAnalogIn::_update()
|
||||
|
||||
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 */
|
||||
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
|
||||
|
||||
@ -130,7 +135,7 @@ void RaspilotAnalogIn::_update()
|
||||
|
||||
for (int16_t i = 0; i < RASPILOT_ADC_MAX_CHANNELS; i++) {
|
||||
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) {
|
||||
source->_value = _dma_packet_rx.regs[i] * 3.3 / 4096.0;
|
@ -1,15 +1,15 @@
|
||||
#ifndef __RaspilotAnalogIn_H__
|
||||
#define __RaspilotAnalogIn_H__
|
||||
#pragma once
|
||||
|
||||
#include <AP_ADC/AP_ADC.h>
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include <AP_ADC/AP_ADC.h>
|
||||
|
||||
#define RASPILOT_ADC_MAX_CHANNELS 8
|
||||
|
||||
class RaspilotAnalogSource: public AP_HAL::AnalogSource {
|
||||
class AnalogSource_Raspilot: public AP_HAL::AnalogSource {
|
||||
public:
|
||||
friend class RaspilotAnalogIn;
|
||||
RaspilotAnalogSource(int16_t pin);
|
||||
AnalogSource_Raspilot(int16_t pin);
|
||||
float read_average();
|
||||
float read_latest();
|
||||
void set_pin(uint8_t p);
|
||||
@ -39,7 +39,7 @@ private:
|
||||
AP_HAL::SPIDeviceDriver *_spi;
|
||||
AP_HAL::Semaphore *_spi_sem;
|
||||
|
||||
RaspilotAnalogSource *_channels[RASPILOT_ADC_MAX_CHANNELS];
|
||||
AnalogSource_Raspilot *_channels[RASPILOT_ADC_MAX_CHANNELS];
|
||||
|
||||
uint8_t _channels_number;
|
||||
|
||||
@ -47,5 +47,3 @@ private:
|
||||
|
||||
uint32_t _last_update_timestamp;
|
||||
};
|
||||
|
||||
#endif
|
Loading…
Reference in New Issue
Block a user