mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
8a31af801f
this changes the ADC code to return the full resolution of the sensors. It also adds a new Ch6() interface that returns 6 channels at once, so the IMU can read 3 accelerometers and 3 gyros at once, and get the exact time that the values were accumulated over
47 lines
1.2 KiB
C++
47 lines
1.2 KiB
C++
#ifndef AP_ADC_H
|
|
#define AP_ADC_H
|
|
|
|
#include <stdint.h>
|
|
|
|
/*
|
|
AP_ADC.cpp - Analog Digital Converter Base Class for Ardupilot Mega
|
|
Code by James Goppert. DIYDrones.com
|
|
|
|
This library is free software; you can redistribute it and/or
|
|
modify it under the terms of the GNU Lesser General Public
|
|
License as published by the Free Software Foundation; either
|
|
version 2.1 of the License, or (at your option) any later version.
|
|
|
|
Methods:
|
|
Init() : Initialization of ADC. (interrupts etc)
|
|
Ch(ch_num) : Return the ADC channel value
|
|
Ch6(channel_numbers, result) : Return 6 ADC channel values
|
|
*/
|
|
|
|
class AP_ADC
|
|
{
|
|
public:
|
|
AP_ADC() {}; // Constructor
|
|
virtual void Init() {};
|
|
|
|
/* read one channel value */
|
|
virtual uint16_t Ch(uint8_t ch_num) = 0;
|
|
|
|
/* read 6 channels values as a set, used by IMU for 3 gyros
|
|
and 3 accelerometeres.
|
|
|
|
Pass in an array of 6 channel numbers and results are
|
|
returned in result[]
|
|
|
|
The function returns the amount of time that the returned
|
|
value has been averaged over, in 2.5 millisecond units
|
|
*/
|
|
virtual uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result) = 0;
|
|
private:
|
|
};
|
|
|
|
#include "AP_ADC_ADS7844.h"
|
|
#include "AP_ADC_HIL.h"
|
|
|
|
#endif
|