mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
updated ADC test for new API
This commit is contained in:
parent
9af7021a98
commit
bd30840518
@ -1,37 +1,52 @@
|
|||||||
|
|
||||||
/*
|
/*
|
||||||
Example of APM_ADC library.
|
Example of APM_ADC library.
|
||||||
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
|
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <FastSerial.h>
|
||||||
#include <AP_ADC.h> // ArduPilot Mega ADC Library
|
#include <AP_ADC.h> // ArduPilot Mega ADC Library
|
||||||
|
|
||||||
unsigned long timer;
|
FastSerialPort0(Serial); // FTDI/console
|
||||||
|
|
||||||
|
unsigned long timer;
|
||||||
AP_ADC_ADS7844 adc;
|
AP_ADC_ADS7844 adc;
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
adc.Init(); // APM ADC initialization
|
Serial.begin(115200, 128, 128);
|
||||||
Serial.begin(57600);
|
Serial.println("ArduPilot Mega ADC library test");
|
||||||
Serial.println("ArduPilot Mega ADC library test");
|
delay(1000);
|
||||||
delay(1000);
|
adc.Init(); // APM ADC initialization
|
||||||
timer = millis();
|
delay(1000);
|
||||||
|
timer = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static const uint8_t channel_map[6] = { 1, 2, 0, 4, 5, 6};
|
||||||
|
static uint16_t sin_count;
|
||||||
|
float v;
|
||||||
|
uint32_t last_usec = 0;
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
int ch;
|
v = sin(millis());
|
||||||
|
sin_count++;
|
||||||
if((millis()- timer) > 20)
|
|
||||||
{
|
if ((millis() - timer) > 200) {
|
||||||
timer = millis();
|
uint16_t result[6];
|
||||||
for (ch=0;ch<7;ch++)
|
uint32_t deltat;
|
||||||
{
|
uint16_t ch3;
|
||||||
Serial.print(adc.Ch(ch));
|
|
||||||
Serial.print(",");
|
timer = millis();
|
||||||
}
|
|
||||||
Serial.println();
|
ch3 = adc.Ch(3);
|
||||||
}
|
deltat = adc.Ch6(channel_map, result);
|
||||||
|
|
||||||
|
Serial.printf("gx=%u gy=%u gz=%u ax=%u ay=%u az=%u gt=%u deltat=%lu sin_count=%u\n",
|
||||||
|
result[0], result[1], result[2],
|
||||||
|
result[3], result[4], result[5],
|
||||||
|
ch3, deltat, sin_count);
|
||||||
|
sin_count = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// end of test program
|
|
||||||
|
Loading…
Reference in New Issue
Block a user