ADC: added an enable_channel() API

enable_channel() must be used before the Ch6() method is called to
enable gathering of data on the required channels
This commit is contained in:
Andrew Tridgell 2011-12-16 20:08:37 +11:00
parent c41e7c505b
commit 9591317dbc
5 changed files with 36 additions and 16 deletions

View File

@ -37,9 +37,14 @@ class AP_ADC
The function returns the amount of time (in microseconds) The function returns the amount of time (in microseconds)
since the last call to Ch6(). since the last call to Ch6().
NOTE: You must enable the channels using enable_channel()
before use
*/ */
virtual uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result) = 0; virtual uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result) = 0;
virtual void enable_channel(const uint8_t ch) = 0;
private: private:
}; };

View File

@ -100,6 +100,7 @@ void AP_ADC_ADS7844::read(void)
return; return;
} }
// build a sequence of commands to use to fetch the channels
for (ch = 0; ch < 8; ch++) { for (ch = 0; ch < 8; ch++) {
if (enable_mask & (1<<ch)) { if (enable_mask & (1<<ch)) {
enable_cmd[num_enabled++] = adc_cmd[ch]; enable_cmd[num_enabled++] = adc_cmd[ch];
@ -187,6 +188,13 @@ void AP_ADC_ADS7844::Init( AP_PeriodicProcess * scheduler )
} }
// enable a channel
void AP_ADC_ADS7844::enable_channel(uint8_t ch)
{
enable_mask |= (1<<ch);
}
// Read one channel value // Read one channel value
float AP_ADC_ADS7844::Ch(uint8_t ch_num) float AP_ADC_ADS7844::Ch(uint8_t ch_num)
{ {
@ -220,10 +228,6 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, uint16_t *result)
uint32_t sum[6]; uint32_t sum[6];
uint8_t i; uint8_t i;
for (i=0; i<6; i++) {
enable_mask |= (1<<channel_numbers[i]);
}
// ensure we have at least one value // ensure we have at least one value
for (i=0; i<6; i++) { for (i=0; i<6; i++) {
while (_count[channel_numbers[i]] == 0) /* noop */; while (_count[channel_numbers[i]] == 0) /* noop */;

View File

@ -29,6 +29,7 @@ class AP_ADC_ADS7844 : public AP_ADC
// Read 6 sensors at once // Read 6 sensors at once
uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result); uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result);
void enable_channel(uint8_t ch);
bool filter_result; bool filter_result;
private: private:

View File

@ -1,24 +1,26 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
Example of APM_ADC library.
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
*/
/*
Example of APM_ADC library.
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
*/
#include <FastSerial.h> #include <FastSerial.h>
#include <Arduino_Mega_ISR_Registry.h> #include <Arduino_Mega_ISR_Registry.h>
#include <AP_PeriodicProcess.h> #include <AP_PeriodicProcess.h>
#include <AP_ADC.h> // ArduPilot Mega ADC Library #include <AP_ADC.h> // ArduPilot Mega ADC Library
FastSerialPort0(Serial); // FTDI/console FastSerialPort0(Serial); // FTDI/console
Arduino_Mega_ISR_Registry isr_registry; Arduino_Mega_ISR_Registry isr_registry;
AP_TimerAperiodicProcess adc_scheduler; AP_TimerAperiodicProcess adc_scheduler;
unsigned long timer; unsigned long timer;
AP_ADC_ADS7844 adc; AP_ADC_ADS7844 adc;
void setup() static const uint8_t channel_map[6] = { 1, 2, 0, 4, 5, 6};
void setup()
{ {
Serial.begin(115200, 128, 128); Serial.begin(115200, 128, 128);
Serial.println("ArduPilot Mega ADC library test"); Serial.println("ArduPilot Mega ADC library test");
@ -30,9 +32,12 @@ void setup()
adc.Init(&adc_scheduler); // APM ADC initialization adc.Init(&adc_scheduler); // APM ADC initialization
delay(1000); delay(1000);
timer = millis(); timer = millis();
for (uint8_t ch=0; ch<6; ch++) {
adc.enable_channel(channel_map[ch]);
}
} }
static const uint8_t channel_map[6] = { 1, 2, 0, 4, 5, 6};
float v; float v;
uint32_t last_usec = 0; uint32_t last_usec = 0;

View File

@ -50,6 +50,11 @@ AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan( AP_ADC * adc ) :
void AP_InertialSensor_Oilpan::init( AP_PeriodicProcess * scheduler) void AP_InertialSensor_Oilpan::init( AP_PeriodicProcess * scheduler)
{ {
_adc->Init(scheduler); _adc->Init(scheduler);
// tell the ADC driver that we will be needed some channels
for (uint8_t ch=0; ch<6; ch++) {
_adc->enable_channel(_sensors[ch]);
}
} }
bool AP_InertialSensor_Oilpan::update() bool AP_InertialSensor_Oilpan::update()