aboutsummaryrefslogtreecommitdiff
path: root/src/drivers/stm32/adc
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-04-28 01:17:12 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-04-28 01:30:14 +0200
commitf57439b90e23de260259dec051d3e2ead2d61c8c (patch)
tree5cd778d2cf0c9afb2851ab9042bbecc5b742a497 /src/drivers/stm32/adc
parent8040b9b96e8f7c07aa981150c33f850096062f70 (diff)
downloadpx4-firmware-f57439b90e23de260259dec051d3e2ead2d61c8c.tar.gz
px4-firmware-f57439b90e23de260259dec051d3e2ead2d61c8c.tar.bz2
px4-firmware-f57439b90e23de260259dec051d3e2ead2d61c8c.zip
Moved all drivers to new world, PX4IO completely in new world
Diffstat (limited to 'src/drivers/stm32/adc')
-rw-r--r--src/drivers/stm32/adc/adc.cpp387
-rw-r--r--src/drivers/stm32/adc/module.mk42
2 files changed, 429 insertions, 0 deletions
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
new file mode 100644
index 000000000..911def943
--- /dev/null
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -0,0 +1,387 @@
+/****************************************************************************
+ *
+ * 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>
+#include <systemlib/perf_counter.h>
+
+/*
+ * Register accessors.
+ * For now, no reason not to just use ADC1.
+ */
+#define REG(_reg) (*(volatile uint32_t *)(STM32_ADC1_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)
+
+#ifdef STM32_ADC_CCR
+# define rCCR REG(STM32_ADC_CCR_OFFSET)
+#endif
+
+class ADC : public device::CDev
+{
+public:
+ ADC(uint32_t channels);
+ ~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 */
+
+ hrt_call _call;
+ perf_counter_t _sample_perf;
+
+ unsigned _channel_count;
+ adc_msg_s *_samples; /**< sample buffer */
+
+ /** work trampoline */
+ static void _tick_trampoline(void *arg);
+
+ /** worker function */
+ void _tick();
+
+ /**
+ * Sample a single channel and return the measured value.
+ *
+ * @param channel The channel to sample.
+ * @return The sampled value, or 0xffff if
+ * sampling failed.
+ */
+ uint16_t _sample(unsigned channel);
+
+};
+
+ADC::ADC(uint32_t channels) :
+ CDev("adc", ADC_DEVICE_PATH),
+ _sample_perf(perf_alloc(PC_ELAPSED, "ADC samples")),
+ _channel_count(0),
+ _samples(nullptr)
+{
+ _debug_enabled = true;
+
+ /* always enable the temperature sensor */
+ channels |= 1 << 16;
+
+ /* allocate the sample array */
+ for (unsigned i = 0; i < 32; i++) {
+ if (channels & (1 << i)) {
+ _channel_count++;
+ }
+ }
+ _samples = new adc_msg_s[_channel_count];
+
+ /* prefill the channel numbers in the sample array */
+ if (_samples != nullptr) {
+ unsigned index = 0;
+ for (unsigned i = 0; i < 32; i++) {
+ if (channels & (1 << i)) {
+ _samples[index].am_channel = i;
+ _samples[index].am_data = 0;
+ index++;
+ }
+ }
+ }
+}
+
+ADC::~ADC()
+{
+ if (_samples != nullptr)
+ delete _samples;
+}
+
+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
+ /* enable the temperature sensor in CR2 */
+ ADC_CR2_TSVREFE |
+#endif
+ 0;
+
+#ifdef ADC_CCR_TSVREFE
+ /* enable temperature sensor in CCR */
+ rCCR = ADC_CCR_TSVREFE;
+#endif
+
+ /* configure for a single-channel sequence */
+ rSQR1 = 0;
+ rSQR2 = 0;
+ rSQR3 = 0; /* 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)
+{
+ const size_t maxsize = sizeof(adc_msg_s) * _channel_count;
+
+ if (len > maxsize)
+ len = maxsize;
+
+ /* block interrupts while copying samples to avoid racing with an update */
+ irqstate_t flags = irqsave();
+ memcpy(buffer, _samples, len);
+ irqrestore(flags);
+
+ return len;
+}
+
+int
+ADC::open_first(struct file *filp)
+{
+ /* get fresh data */
+ _tick();
+
+ /* and schedule regular updates */
+ 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()
+{
+ /* scan the channel set and sample each */
+ for (unsigned i = 0; i < _channel_count; i++)
+ _samples[i].am_data = _sample(_samples[i].am_channel);
+}
+
+uint16_t
+ADC::_sample(unsigned channel)
+{
+ perf_begin(_sample_perf);
+
+ /* clear any previous EOC */
+ if (rSR & ADC_SR_EOC)
+ rSR &= ~ADC_SR_EOC;
+
+ /* 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;
+
+ perf_end(_sample_perf);
+ return result;
+}
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int adc_main(int argc, char *argv[]);
+
+namespace
+{
+ADC *g_adc;
+
+void
+test(void)
+{
+
+ int fd = open(ADC_DEVICE_PATH, O_RDONLY);
+ if (fd < 0)
+ err(1, "can't open ADC device");
+
+ for (unsigned i = 0; i < 50; i++) {
+ adc_msg_s data[8];
+ ssize_t count = read(fd, data, sizeof(data));
+
+ if (count < 0)
+ errx(1, "read error");
+
+ unsigned channels = count / sizeof(data[0]);
+
+ for (unsigned j = 0; j < channels; j++) {
+ printf ("%d: %u ", data[j].am_channel, data[j].am_data);
+ }
+
+ printf("\n");
+ usleep(500000);
+ }
+
+ exit(0);
+}
+}
+
+int
+adc_main(int argc, char *argv[])
+{
+ if (g_adc == nullptr) {
+ /* XXX this hardcodes the default channel set for PX4FMU - should be configurable */
+ g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
+
+ 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);
+}
diff --git a/src/drivers/stm32/adc/module.mk b/src/drivers/stm32/adc/module.mk
new file mode 100644
index 000000000..48620feea
--- /dev/null
+++ b/src/drivers/stm32/adc/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2012, 2013 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
+#
+
+MODULE_COMMAND = adc
+
+SRCS = adc.cpp
+
+INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common