mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Switch ArducopterNG to use AP_ADC library.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@950 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
a6c315b6f1
commit
cfae8490d5
@ -28,7 +28,7 @@
|
||||
/* Mounting position : RC connectors pointing backwards */
|
||||
/* This code use this libraries : */
|
||||
/* APM_RC : Radio library (with InstantPWM) */
|
||||
/* APM_ADC : External ADC library */
|
||||
/* AP_ADC : External ADC library */
|
||||
/* DataFlash : DataFlash log library */
|
||||
/* APM_BMP085 : BMP085 barometer library */
|
||||
/* APM_Compass : HMC5843 compass library [optional] */
|
||||
@ -164,7 +164,7 @@
|
||||
#include <avr/pgmspace.h>
|
||||
#include <math.h>
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <APM_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <APM_BMP085.h> // ArduPilot Mega BMP085 Library
|
||||
#include <DataFlash.h> // ArduPilot Mega Flash Memory Library
|
||||
#include <APM_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
@ -190,7 +190,7 @@
|
||||
#define VER 1.52 // Current software version (only numeric values)
|
||||
|
||||
// Sensors - declare one global instance
|
||||
APM_ADC_Class APM_ADC;
|
||||
AP_ADC_ADS7844 adc;
|
||||
APM_BMP085_Class APM_BMP085;
|
||||
APM_Compass_Class APM_Compass;
|
||||
|
||||
@ -231,7 +231,7 @@ void setup() {
|
||||
/* ************** MAIN PROGRAM - MAIN LOOP ******************** */
|
||||
/* ************************************************************ */
|
||||
|
||||
// Sensor reading loop is inside APM_ADC and runs at 400Hz (based on Timer2 interrupt)
|
||||
// Sensor reading loop is inside AP_ADC and runs at 400Hz (based on Timer2 interrupt)
|
||||
|
||||
// * fast rate loop => Main loop => 200Hz
|
||||
// read sensors
|
||||
|
@ -175,7 +175,7 @@ void CALIB_AccOffset() {
|
||||
uint8_t loopy;
|
||||
uint16_t xx = 0, xy = 0, xz = 0;
|
||||
|
||||
APM_ADC.Init(); // APM ADC library initialization
|
||||
adc.Init(); // APM ADC library initialization
|
||||
// delay(250); // Giving small moment before starting
|
||||
|
||||
calibrateSensors(); // Calibrate neutral values of gyros (in Sensors.pde)
|
||||
@ -195,11 +195,11 @@ void CALIB_AccOffset() {
|
||||
tab();
|
||||
SerPrln(xz += read_adc(5));
|
||||
*/
|
||||
SerPri(xx += APM_ADC.Ch(4));
|
||||
SerPri(xx += adc.Ch(4));
|
||||
tab();
|
||||
SerPri(xy += APM_ADC.Ch(5));
|
||||
SerPri(xy += adc.Ch(5));
|
||||
tab();
|
||||
SerPrln(xz += APM_ADC.Ch(3));
|
||||
SerPrln(xz += adc.Ch(3));
|
||||
|
||||
|
||||
|
||||
|
@ -40,7 +40,7 @@ TODO:
|
||||
#include "WProgram.h"
|
||||
#include <Wire.h>
|
||||
#include <EEPROM.h> // added by Randy
|
||||
#include <APM_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <APM_Compass.h> // ArduPilot Mega Compass Library
|
||||
#include <DataFlash.h> // ArduPilot Mega DataFlash Library.
|
||||
|
@ -32,7 +32,7 @@ void Read_adc_raw(void)
|
||||
//int temp;
|
||||
|
||||
for (int i=0;i<6;i++)
|
||||
AN[i] = APM_ADC.Ch(sensors[i]);
|
||||
AN[i] = adc.Ch(sensors[i]);
|
||||
}
|
||||
|
||||
// Returns an analog value with the offset
|
||||
|
@ -79,7 +79,7 @@ void APM_Init() {
|
||||
// Wiggle LEDs while ESCs are rebooting
|
||||
FullBlink(50,20);
|
||||
|
||||
APM_ADC.Init(); // APM ADC library initialization
|
||||
adc.Init(); // APM ADC library initialization
|
||||
DataFlash.Init(); // DataFlash log initialization
|
||||
|
||||
#ifdef IsGPS
|
||||
|
Loading…
Reference in New Issue
Block a user