AP_ADC: rework ADC library to use PeriodicProcess and ISR_Register

this makes it possible to build the ADC library when another driver
may also want that interrupt
This commit is contained in:
Pat Hickey 2011-11-13 14:12:53 +11:00
parent 7474a8be53
commit 6d876bc54d
7 changed files with 54 additions and 50 deletions

View File

@ -2,6 +2,8 @@
#define AP_ADC_H
#include <stdint.h>
#include <stdlib.h>
#include <../AP_PeriodicProcess/AP_PeriodicProcess.h>
/*
AP_ADC.cpp - Analog Digital Converter Base Class for Ardupilot Mega
@ -22,7 +24,7 @@ class AP_ADC
{
public:
AP_ADC() {}; // Constructor
virtual void Init() {};
virtual void Init(AP_PeriodicProcess * scheduler = NULL) = 0;
/* read one channel value */
virtual uint16_t Ch(uint8_t ch_num) = 0;

View File

@ -83,10 +83,9 @@ static inline unsigned char ADC_SPI_transfer(unsigned char data)
}
ISR (TIMER2_OVF_vect)
void AP_ADC_ADS7844::read(void)
{
uint8_t ch;
static uint8_t timer_offset;
bit_clear(PORTC, 4); // Enable Chip Select (PIN PC4)
ADC_SPI_transfer(adc_cmd[0]); // Command to read the first channel
@ -119,10 +118,6 @@ ISR (TIMER2_OVF_vect)
bit_set(PORTC, 4); // Disable Chip Select (PIN PC4)
// this gives us a sample rate between 781Hz and 1302Hz. We
// randomise it to try to minimise aliasing effects
timer_offset = (timer_offset + 49) % 32;
TCNT2 = TCNT2_781_HZ + timer_offset;
}
@ -134,7 +129,7 @@ AP_ADC_ADS7844::AP_ADC_ADS7844() :
}
// Public Methods //////////////////////////////////////////////////////////////
void AP_ADC_ADS7844::Init(void)
void AP_ADC_ADS7844::Init( AP_PeriodicProcess * scheduler )
{
pinMode(ADC_CHIP_SELECT, OUTPUT);
@ -162,13 +157,8 @@ void AP_ADC_ADS7844::Init(void)
last_ch6_micros = micros();
// Enable Timer2 Overflow interrupt to capture ADC data
TIMSK2 = 0; // Disable interrupts
TCCR2A = 0; // normal counting mode
TCCR2B = _BV(CS21) | _BV(CS22); // Set prescaler of clk/256
TCNT2 = 0;
TIFR2 = _BV(TOV2); // clear pending interrupts;
TIMSK2 = _BV(TOIE2); // enable the overflow interrupt
scheduler->register_process( AP_ADC_ADS7844::read );
}
// Read one channel value

View File

@ -14,13 +14,14 @@
#define ADC_ACCEL_FILTER_SIZE 8
#include "AP_ADC.h"
#include "../AP_PeriodicProcess/AP_PeriodicProcess.h"
#include <inttypes.h>
class AP_ADC_ADS7844 : public AP_ADC
{
public:
AP_ADC_ADS7844(); // Constructor
void Init();
void Init( AP_PeriodicProcess * scheduler );
// Read 1 sensor value
uint16_t Ch(unsigned char ch_num);
@ -34,6 +35,7 @@ class AP_ADC_ADS7844 : public AP_ADC
uint16_t _prev_gyro[3];
uint16_t _prev_accel[3];
uint8_t _filter_index_accel;
static void read( void );
};

View File

@ -39,7 +39,7 @@ AP_ADC_HIL::AP_ADC_HIL()
last_hil_time = millis();
}
void AP_ADC_HIL::Init(void)
void AP_ADC_HIL::Init( AP_PeriodicProcess * scheduler )
{
}

View File

@ -28,7 +28,7 @@ class AP_ADC_HIL : public AP_ADC
///
// Initializes sensor, part of public AP_ADC interface
void Init();
void Init(AP_PeriodicProcess*);
///
// Read the sensor, part of public AP_ADC interface

View File

@ -5,10 +5,16 @@
*/
#include <FastSerial.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <AP_PeriodicProcess.h>
#include <AP_ADC.h> // ArduPilot Mega ADC Library
FastSerialPort0(Serial); // FTDI/console
Arduino_Mega_ISR_Registry isr_registry;
AP_TimerAperiodicProcess adc_scheduler;
unsigned long timer;
AP_ADC_ADS7844 adc;
@ -17,7 +23,11 @@ void setup()
Serial.begin(115200, 128, 128);
Serial.println("ArduPilot Mega ADC library test");
delay(1000);
adc.Init(); // APM ADC initialization
isr_registry.init();
adc_scheduler.init(&isr_registry);
adc.Init(&adc_scheduler); // APM ADC initialization
delay(1000);
timer = millis();
}

View File

@ -1,2 +1,2 @@
BOARD = mega
BOARD = mega2560
include ../../../AP_Common/Arduino.mk