mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
AP_AnalogSource: obsoleted by AP_HAL. Renamed to AP_ADC_AnalogSource.
This commit is contained in:
parent
dfc8e91fd3
commit
ce8dc5fd5c
@ -1,8 +1,7 @@
|
|||||||
|
|
||||||
#include "AP_AnalogSource_ADC.h"
|
#include "AP_AnalogSource_ADC.h"
|
||||||
|
|
||||||
float AP_AnalogSource_ADC::read(void)
|
float AP_ADC_AnalogSource::read() {
|
||||||
{
|
|
||||||
float fullscale = _adc->Ch(_ch);
|
float fullscale = _adc->Ch(_ch);
|
||||||
float scaled = _prescale * fullscale;
|
float scaled = _prescale * fullscale;
|
||||||
return scaled;
|
return scaled;
|
22
libraries/AP_ADC_AnalogSource/AP_ADC_AnalogSource.h
Normal file
22
libraries/AP_ADC_AnalogSource/AP_ADC_AnalogSource.h
Normal file
@ -0,0 +1,22 @@
|
|||||||
|
|
||||||
|
#ifndef __AP_ADC_ANALOG_SOURCE_H__
|
||||||
|
#define __AP_ADC_ANALOG_SOURCE_H__
|
||||||
|
|
||||||
|
#include <AP_ADC.h>
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
|
class AP_ADC_AnalogSource : public AP_HAL::AnalogSource
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
AP_ADC_AnalogSource( AP_ADC * adc, uint8_t ch, float prescale = 1.0 ) :
|
||||||
|
_adc(adc), _ch(ch), _prescale(prescale)
|
||||||
|
{}
|
||||||
|
float read(void);
|
||||||
|
|
||||||
|
private:
|
||||||
|
AP_ADC * _adc;
|
||||||
|
uint8_t _ch;
|
||||||
|
float _prescale;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // __AP_ADC_ANALOG_SOURCE_H__
|
@ -1,8 +0,0 @@
|
|||||||
|
|
||||||
#ifndef __AP_ANALOG_SOURCE_H__
|
|
||||||
#define __AP_ANALOG_SOURCE_H__
|
|
||||||
|
|
||||||
#include "AP_AnalogSource_Arduino.h"
|
|
||||||
#include "AP_AnalogSource_ADC.h"
|
|
||||||
|
|
||||||
#endif // __AP_ANALOG_SOURCE_H__
|
|
@ -1,22 +0,0 @@
|
|||||||
|
|
||||||
#ifndef __AP_ANALOG_SOURCE_ADC_H__
|
|
||||||
#define __AP_ANALOG_SOURCE_ADC_H__
|
|
||||||
|
|
||||||
#include "AnalogSource.h"
|
|
||||||
#include "../AP_ADC/AP_ADC.h"
|
|
||||||
|
|
||||||
class AP_AnalogSource_ADC : public AP_AnalogSource
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
AP_AnalogSource_ADC( AP_ADC * adc, uint8_t ch, float prescale = 1.0 ) :
|
|
||||||
_adc(adc), _ch(ch), _prescale(prescale) {
|
|
||||||
}
|
|
||||||
float read(void);
|
|
||||||
|
|
||||||
private:
|
|
||||||
AP_ADC * _adc;
|
|
||||||
uint8_t _ch;
|
|
||||||
float _prescale;
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // __AP_ANALOG_SOURCE_ADC_H__
|
|
@ -1,50 +0,0 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#ifndef __AP_ANALOG_SOURCE_ARDUINO_H__
|
|
||||||
#define __AP_ANALOG_SOURCE_ARDUINO_H__
|
|
||||||
|
|
||||||
#include "AnalogSource.h"
|
|
||||||
#include "AP_PeriodicProcess.h"
|
|
||||||
|
|
||||||
// special pin number which is interpreted as a
|
|
||||||
// internal Vcc voltage read
|
|
||||||
#define ANALOG_PIN_VCC 254
|
|
||||||
#define ANALOG_PIN_NONE 255
|
|
||||||
|
|
||||||
class AP_AnalogSource_Arduino : public AP_AnalogSource
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
AP_AnalogSource_Arduino( uint8_t pin, float prescale = 1.0 ) :
|
|
||||||
_prescale(prescale) {
|
|
||||||
_assign_pin_index(pin);
|
|
||||||
}
|
|
||||||
|
|
||||||
// setup the timer callback
|
|
||||||
static void init_timer(AP_PeriodicProcess * scheduler);
|
|
||||||
|
|
||||||
// read a value with a prescale
|
|
||||||
float read(void);
|
|
||||||
|
|
||||||
// read the raw 16 bit ADC value
|
|
||||||
uint16_t read_raw(void);
|
|
||||||
|
|
||||||
// read a Vcc value in millivolts
|
|
||||||
uint16_t read_vcc(void);
|
|
||||||
|
|
||||||
// read the average 16 bit ADC value since
|
|
||||||
// we last called read_average().
|
|
||||||
float read_average(void);
|
|
||||||
|
|
||||||
// set the pin to be used for this source. This allows for the pin
|
|
||||||
// to be changed at runtime
|
|
||||||
void set_pin(uint8_t pin);
|
|
||||||
|
|
||||||
private:
|
|
||||||
uint8_t _pin_index;
|
|
||||||
float _prescale;
|
|
||||||
|
|
||||||
uint8_t _remap_pin(uint8_t pin);
|
|
||||||
void _assign_pin_index(uint8_t pin);
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // __AP_ANALOG_SOURCE_ARDUINO_H__
|
|
@ -1,11 +0,0 @@
|
|||||||
|
|
||||||
#ifndef __ANALOG_SOURCE_H__
|
|
||||||
#define __ANALOG_SOURCE_H__
|
|
||||||
|
|
||||||
class AP_AnalogSource
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
virtual float read(void) = 0;
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // __ANALOG_SOURCE_H__
|
|
@ -1,42 +0,0 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
||||||
/*
|
|
||||||
* Example of AnalogSource Arduino
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <FastSerial.h>
|
|
||||||
#include <AP_Math.h>
|
|
||||||
#include <AP_Common.h>
|
|
||||||
#include <AP_Param.h>
|
|
||||||
#include <Arduino_Mega_ISR_Registry.h>
|
|
||||||
#include <AP_PeriodicProcess.h>
|
|
||||||
#include <AP_AnalogSource.h>
|
|
||||||
|
|
||||||
Arduino_Mega_ISR_Registry isr_registry;
|
|
||||||
AP_TimerProcess scheduler;
|
|
||||||
|
|
||||||
FastSerialPort0(Serial);
|
|
||||||
|
|
||||||
AP_AnalogSource_Arduino vcc_source(ANALOG_PIN_VCC);
|
|
||||||
AP_AnalogSource_Arduino pin0(0);
|
|
||||||
AP_AnalogSource_Arduino pin1(1);
|
|
||||||
|
|
||||||
|
|
||||||
void setup()
|
|
||||||
{
|
|
||||||
Serial.begin(115200);
|
|
||||||
isr_registry.init();
|
|
||||||
scheduler.init(&isr_registry);
|
|
||||||
AP_AnalogSource_Arduino::init_timer(&scheduler);
|
|
||||||
}
|
|
||||||
|
|
||||||
void loop()
|
|
||||||
{
|
|
||||||
while (true) {
|
|
||||||
delay(1000);
|
|
||||||
Serial.printf("Vcc: %u PIN0: %u PIN1: %u PIN1_avg: %u\n",
|
|
||||||
(unsigned)vcc_source.read_vcc(),
|
|
||||||
(unsigned)pin0.read_raw(),
|
|
||||||
(unsigned)pin1.read_raw(),
|
|
||||||
(unsigned)pin1.read_average());
|
|
||||||
}
|
|
||||||
}
|
|
@ -1,2 +0,0 @@
|
|||||||
BOARD = mega
|
|
||||||
include ../../../AP_Common/Arduino.mk
|
|
Loading…
Reference in New Issue
Block a user