forked from Archive/PX4-Autopilot
First cut at a simple® ADC driver built on our driver framework.
This commit is contained in:
parent
476db46869
commit
22f5a1dc94
|
@ -1,139 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_adc.c
|
||||
*
|
||||
* Board-specific ADC functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "stm32_adc.h"
|
||||
#include "px4fmu_internal.h"
|
||||
|
||||
#define ADC3_NCHANNELS 4
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
/* The PX4FMU board has four ADC channels: ADC323 IN10-13
|
||||
*/
|
||||
|
||||
/* Identifying number of each ADC channel: Variable Resistor. */
|
||||
|
||||
#ifdef CONFIG_STM32_ADC3
|
||||
static const uint8_t g_chanlist[ADC3_NCHANNELS] = {10, 11};// , 12, 13}; ADC12 and 13 are used by MPU on v1.5 boards
|
||||
|
||||
/* Configurations of pins used byte each ADC channels */
|
||||
static const uint32_t g_pinlist[ADC3_NCHANNELS] = {GPIO_ADC3_IN10, GPIO_ADC3_IN11}; // ADC12 and 13 are used by MPU on v1.5 boards, GPIO_ADC3_IN12, GPIO_ADC3_IN13};
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: adc_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/adc.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int adc_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct adc_dev_s *adc[ADC3_NCHANNELS];
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized) {
|
||||
char name[11];
|
||||
|
||||
for (i = 0; i < ADC3_NCHANNELS; i++) {
|
||||
stm32_configgpio(g_pinlist[i]);
|
||||
}
|
||||
|
||||
for (i = 0; i < 1; i++) {
|
||||
/* Configure the pins as analog inputs for the selected channels */
|
||||
//stm32_configgpio(g_pinlist[i]);
|
||||
|
||||
/* Call stm32_adcinitialize() to get an instance of the ADC interface */
|
||||
//multiple channels only supported with dma!
|
||||
adc[i] = stm32_adcinitialize(3, (g_chanlist), 4);
|
||||
|
||||
if (adc == NULL) {
|
||||
adbg("ERROR: Failed to get ADC interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
|
||||
/* Register the ADC driver at "/dev/adc0" */
|
||||
sprintf(name, "/dev/adc%d", i);
|
||||
ret = adc_register(name, adc[i]);
|
||||
|
||||
if (ret < 0) {
|
||||
adbg("adc_register failed for adc %s: %d\n", name, ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -209,8 +209,7 @@ __EXPORT int nsh_archinitialize(void)
|
|||
|
||||
message("[boot] Successfully initialized SPI port 1\r\n");
|
||||
|
||||
#if defined(CONFIG_STM32_SPI3)
|
||||
/* Get the SPI port */
|
||||
/* Get the SPI port for the microSD slot */
|
||||
|
||||
message("[boot] Initializing SPI port 3\n");
|
||||
spi3 = up_spiinitialize(3);
|
||||
|
@ -233,23 +232,11 @@ __EXPORT int nsh_archinitialize(void)
|
|||
}
|
||||
|
||||
message("[boot] Successfully bound SPI port 3 to the MMCSD driver\n");
|
||||
#endif /* SPI3 */
|
||||
|
||||
#ifdef CONFIG_ADC
|
||||
int adc_state = adc_devinit();
|
||||
|
||||
if (adc_state != OK) {
|
||||
/* Try again */
|
||||
adc_state = adc_devinit();
|
||||
|
||||
if (adc_state != OK) {
|
||||
/* Give up */
|
||||
message("[boot] FAILED adc_devinit: %d\n", adc_state);
|
||||
return -ENODEV;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
stm32_configgpio(GPIO_ADC1_IN10);
|
||||
stm32_configgpio(GPIO_ADC1_IN11);
|
||||
//stm32_configgpio(GPIO_ADC1_IN12); // XXX is this available?
|
||||
//stm32_configgpio(GPIO_ADC1_IN13); // jumperable to MPU6000 DRDY on some boards
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
|
@ -0,0 +1,54 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file drv_adc.h
|
||||
*
|
||||
* ADC driver interface.
|
||||
*
|
||||
* This defines additional operations over and above the standard NuttX
|
||||
* ADC API.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
#include <nuttx/compiler.h>
|
||||
|
||||
#define ADC_DEVICE_PATH "/dev/adc0"
|
||||
|
||||
/*
|
||||
* ioctl definitions
|
||||
*/
|
|
@ -0,0 +1,43 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# STM32 ADC driver
|
||||
#
|
||||
|
||||
APPNAME = adc
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 2048
|
||||
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
|
@ -0,0 +1,310 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file adc.cpp
|
||||
*
|
||||
* Driver for the STM32 ADC.
|
||||
*
|
||||
* This is a low-rate driver, designed for sampling things like voltages
|
||||
* and so forth. It avoids the gross complexity of the NuttX ADC driver.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <drivers/device/device.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_adc.h>
|
||||
|
||||
#include <arch/stm32/chip.h>
|
||||
#include <stm32_internal.h>
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#define ADC_BASE STM32_ADC1_BASE
|
||||
|
||||
/*
|
||||
* Register accessors.
|
||||
*/
|
||||
#define REG(_reg) (*(volatile uint32_t *)(_base + _reg))
|
||||
|
||||
#define rSR REG(STM32_ADC_SR_OFFSET)
|
||||
#define rCR1 REG(STM32_ADC_CR1_OFFSET)
|
||||
#define rCR2 REG(STM32_ADC_CR2_OFFSET)
|
||||
#define rSMPR1 REG(STM32_ADC_SMPR1_OFFSET)
|
||||
#define rSMPR2 REG(STM32_ADC_SMPR2_OFFSET)
|
||||
#define rJOFR1 REG(STM32_ADC_JOFR1_OFFSET)
|
||||
#define rJOFR2 REG(STM32_ADC_JOFR2_OFFSET)
|
||||
#define rJOFR3 REG(STM32_ADC_JOFR3_OFFSET)
|
||||
#define rJOFR4 REG(STM32_ADC_JOFR4_OFFSET)
|
||||
#define rHTR REG(STM32_ADC_HTR_OFFSET)
|
||||
#define rLTR REG(STM32_ADC_LTR_OFFSET)
|
||||
#define rSQR1 REG(STM32_ADC_SQR1_OFFSET)
|
||||
#define rSQR2 REG(STM32_ADC_SQR2_OFFSET)
|
||||
#define rSQR3 REG(STM32_ADC_SQR3_OFFSET)
|
||||
#define rJSQR REG(STM32_ADC_JSQR_OFFSET)
|
||||
#define rJDR1 REG(STM32_ADC_JDR1_OFFSET)
|
||||
#define rJDR2 REG(STM32_ADC_JDR2_OFFSET)
|
||||
#define rJDR3 REG(STM32_ADC_JDR3_OFFSET)
|
||||
#define rJDR4 REG(STM32_ADC_JDR4_OFFSET)
|
||||
#define rDR REG(STM32_ADC_DR_OFFSET)
|
||||
|
||||
class ADC : public device::CDev
|
||||
{
|
||||
public:
|
||||
ADC();
|
||||
~ADC();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
virtual ssize_t read(file *filp, char *buffer, size_t len);
|
||||
|
||||
protected:
|
||||
virtual int open_first(struct file *filp);
|
||||
virtual int close_last(struct file *filp);
|
||||
|
||||
private:
|
||||
static const hrt_abstime _tickrate = 10000; /* 100Hz base rate */
|
||||
static const uint32_t _base = ADC_BASE;
|
||||
|
||||
hrt_call _call;
|
||||
|
||||
static void _tick_trampoline(void *arg);
|
||||
void _tick();
|
||||
|
||||
uint16_t _sample(unsigned channel);
|
||||
|
||||
uint16_t _result;
|
||||
};
|
||||
|
||||
ADC::ADC() :
|
||||
CDev("adc", ADC_DEVICE_PATH)
|
||||
{
|
||||
_debug_enabled = true;
|
||||
}
|
||||
|
||||
ADC::~ADC()
|
||||
{
|
||||
}
|
||||
|
||||
int
|
||||
ADC::init()
|
||||
{
|
||||
/* do calibration if supported */
|
||||
#ifdef ADC_CR2_CAL
|
||||
rCR2 |= ADC_CR2_CAL;
|
||||
usleep(100);
|
||||
if (rCR2 & ADC_CR2_CAL)
|
||||
return -1;
|
||||
#endif
|
||||
|
||||
/* arbitrarily configure all channels for 55 cycle sample time */
|
||||
rSMPR1 = 0b00000011011011011011011011011011;
|
||||
rSMPR2 = 0b00011011011011011011011011011011;
|
||||
|
||||
/* XXX for F2/4, might want to select 12-bit mode? */
|
||||
rCR1 = 0;
|
||||
|
||||
/* enable the temperature sensor / Vrefint channel if supported*/
|
||||
rCR2 =
|
||||
#ifdef ADC_CR2_TSVREFE
|
||||
ADC_CR2_TSVREFE |
|
||||
#endif
|
||||
0;
|
||||
|
||||
/* configure for a single-channel sequence */
|
||||
rSQR1 = 0;
|
||||
rSQR2 = 0;
|
||||
rSQR3 = 11; /* will be updated with the channel each tick */
|
||||
|
||||
/* power-cycle the ADC and turn it on */
|
||||
rCR2 &= ~ADC_CR2_ADON;
|
||||
usleep(10);
|
||||
rCR2 |= ADC_CR2_ADON;
|
||||
usleep(10);
|
||||
rCR2 |= ADC_CR2_ADON;
|
||||
usleep(10);
|
||||
|
||||
/* kick off a sample and wait for it to complete */
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
rCR2 |= ADC_CR2_SWSTART;
|
||||
while (!(rSR & ADC_SR_EOC)) {
|
||||
|
||||
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 500) {
|
||||
log("sample timeout");
|
||||
return -1;
|
||||
return 0xffff;
|
||||
}
|
||||
}
|
||||
debug("init done");
|
||||
|
||||
/* create the device node */
|
||||
return CDev::init();
|
||||
}
|
||||
|
||||
int
|
||||
ADC::ioctl(file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
return -ENOTTY;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
ADC::read(file *filp, char *buffer, size_t len)
|
||||
{
|
||||
if (len > sizeof(_result))
|
||||
len = sizeof(_result);
|
||||
|
||||
// _result = _sample(11);
|
||||
|
||||
memcpy(buffer, &_result, len);
|
||||
return len;
|
||||
}
|
||||
|
||||
int
|
||||
ADC::open_first(struct file *filp)
|
||||
{
|
||||
hrt_call_every(&_call, _tickrate, _tickrate, _tick_trampoline, this);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
ADC::close_last(struct file *filp)
|
||||
{
|
||||
hrt_cancel(&_call);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
ADC::_tick_trampoline(void *arg)
|
||||
{
|
||||
((ADC *)arg)->_tick();
|
||||
}
|
||||
|
||||
void
|
||||
ADC::_tick()
|
||||
{
|
||||
_result = _sample(11);
|
||||
}
|
||||
|
||||
uint16_t
|
||||
ADC::_sample(unsigned channel)
|
||||
{
|
||||
/* run a single conversion right now - should take about 60 cycles (a few microseconds) max */
|
||||
rSQR3 = channel;
|
||||
rCR2 |= ADC_CR2_SWSTART;
|
||||
|
||||
/* wait for the conversion to complete */
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
while (!(rSR & ADC_SR_EOC)) {
|
||||
|
||||
/* don't wait for more than 50us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 50) {
|
||||
log("sample timeout");
|
||||
return 0xffff;
|
||||
}
|
||||
}
|
||||
|
||||
/* read the result and clear EOC */
|
||||
uint16_t result = rDR;
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/*
|
||||
* Driver 'main' command.
|
||||
*/
|
||||
extern "C" __EXPORT int adc_main(int argc, char *argv[]);
|
||||
|
||||
namespace
|
||||
{
|
||||
ADC *g_adc;
|
||||
|
||||
void
|
||||
test(void)
|
||||
{
|
||||
int fd;
|
||||
|
||||
fd = open(ADC_DEVICE_PATH, O_RDONLY);
|
||||
if (fd < 0)
|
||||
err(1, "can't open ADC device");
|
||||
|
||||
uint16_t value;
|
||||
|
||||
for (unsigned i = 0; i < 50; i++) {
|
||||
if (read(fd, &value, sizeof(value)) != sizeof(value))
|
||||
errx(1, "short read");
|
||||
printf(" %d\n", value);
|
||||
usleep(500000);
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
adc_main(int argc, char *argv[])
|
||||
{
|
||||
if (g_adc == nullptr) {
|
||||
g_adc = new ADC;
|
||||
|
||||
if (g_adc == nullptr)
|
||||
errx(1, "couldn't allocate the ADC driver");
|
||||
|
||||
if (g_adc->init() != OK) {
|
||||
delete g_adc;
|
||||
errx(1, "ADC init failed");
|
||||
}
|
||||
}
|
||||
|
||||
if (argc > 1) {
|
||||
if (!strcmp(argv[1], "test"))
|
||||
test();
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
Loading…
Reference in New Issue