aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorMark Charlebois <charlebm@gmail.com>2015-04-09 10:24:41 -0700
committerMark Charlebois <charlebm@gmail.com>2015-04-20 11:35:48 -0700
commitddf75dd55ae17d70a65bfb58a3b1fe70fff09783 (patch)
tree0ac59e69e0737691164a32e5624e3100f10f7526
parent2eaa2f06e7717f3b19e808f917c5306a19fa16c7 (diff)
downloadpx4-firmware-ddf75dd55ae17d70a65bfb58a3b1fe70fff09783.tar.gz
px4-firmware-ddf75dd55ae17d70a65bfb58a3b1fe70fff09783.tar.bz2
px4-firmware-ddf75dd55ae17d70a65bfb58a3b1fe70fff09783.zip
Linux: added ADC simulator
The sensor module is now able to run after the simulation modules are started. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
-rw-r--r--makefiles/linux/config_linux_default.mk1
-rw-r--r--src/platforms/linux/drivers/adcsim/adcsim.cpp303
-rw-r--r--src/platforms/linux/drivers/adcsim/module.mk42
-rw-r--r--src/platforms/px4_adc.h6
4 files changed, 350 insertions, 2 deletions
diff --git a/makefiles/linux/config_linux_default.mk b/makefiles/linux/config_linux_default.mk
index b7bfd9392..4cd7ac4e2 100644
--- a/makefiles/linux/config_linux_default.mk
+++ b/makefiles/linux/config_linux_default.mk
@@ -60,6 +60,7 @@ MODULES += lib/conversion
MODULES += platforms/linux/px4_layer
MODULES += platforms/linux/drivers/accelsim
MODULES += platforms/linux/drivers/gyrosim
+MODULES += platforms/linux/drivers/adcsim
#
# Unit tests
diff --git a/src/platforms/linux/drivers/adcsim/adcsim.cpp b/src/platforms/linux/drivers/adcsim/adcsim.cpp
new file mode 100644
index 000000000..f676d03d9
--- /dev/null
+++ b/src/platforms/linux/drivers/adcsim/adcsim.cpp
@@ -0,0 +1,303 @@
+/****************************************************************************
+ *
+ * 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 ADCSIM.
+ *
+ * This is a low-rate driver, designed for sampling things like voltages
+ * and so forth. It avoids the gross complexity of the NuttX ADCSIM driver.
+ */
+
+#include <px4_config.h>
+#include <px4_adc.h>
+#include <board_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 <systemlib/err.h>
+#include <systemlib/perf_counter.h>
+
+#include <uORB/topics/system_power.h>
+
+
+class ADCSIM : public device::VDev
+{
+public:
+ ADCSIM(uint32_t channels);
+ ~ADCSIM();
+
+ virtual int init();
+
+ virtual int ioctl(device::px4_dev_handle_t *handlep, int cmd, unsigned long arg);
+ virtual ssize_t read(device::px4_dev_handle_t *handlep, char *buffer, size_t len);
+
+protected:
+ virtual int open_first(device::px4_dev_handle_t *handlep);
+ virtual int close_last(device::px4_dev_handle_t *handlep);
+
+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 */
+
+ orb_advert_t _to_system_power;
+
+ /** 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);
+
+ // update system_power ORB topic, only on FMUv2
+ void update_system_power(void);
+};
+
+ADCSIM::ADCSIM(uint32_t channels) :
+ VDev("adc", ADCSIM0_DEVICE_PATH),
+ _sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")),
+ _channel_count(0),
+ _samples(nullptr),
+ _to_system_power(0)
+{
+ _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++;
+ }
+ }
+ }
+}
+
+ADCSIM::~ADCSIM()
+{
+ if (_samples != nullptr)
+ delete _samples;
+}
+
+int
+ADCSIM::init()
+{
+ debug("init done");
+
+ /* create the device node */
+ return VDev::init();
+}
+
+int
+ADCSIM::ioctl(device::px4_dev_handle_t *handlep, int cmd, unsigned long arg)
+{
+ return -ENOTTY;
+}
+
+ssize_t
+ADCSIM::read(device::px4_dev_handle_t *handlep, 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 */
+ memcpy(buffer, _samples, len);
+
+ return len;
+}
+
+int
+ADCSIM::open_first(device::px4_dev_handle_t *handlep)
+{
+ /* get fresh data */
+ _tick();
+
+ /* and schedule regular updates */
+ hrt_call_every(&_call, _tickrate, _tickrate, _tick_trampoline, this);
+
+ return 0;
+}
+
+int
+ADCSIM::close_last(device::px4_dev_handle_t *handlep)
+{
+ hrt_cancel(&_call);
+ return 0;
+}
+
+void
+ADCSIM::_tick_trampoline(void *arg)
+{
+ (reinterpret_cast<ADCSIM *>(arg))->_tick();
+}
+
+void
+ADCSIM::_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);
+ update_system_power();
+}
+
+void
+ADCSIM::update_system_power(void)
+{
+}
+
+uint16_t
+ADCSIM::_sample(unsigned channel)
+{
+ perf_begin(_sample_perf);
+
+ uint16_t result = 1;
+
+ perf_end(_sample_perf);
+ return result;
+}
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int adc_main(int argc, char *argv[]);
+
+namespace
+{
+ADCSIM *g_adc;
+
+int
+test(void)
+{
+
+ int fd = px4_open(ADCSIM0_DEVICE_PATH, O_RDONLY);
+ if (fd < 0) {
+ warnx("can't open ADCSIM device");
+ return 1;
+ }
+
+ for (unsigned i = 0; i < 50; i++) {
+ adc_msg_s data[12];
+ ssize_t count = read(fd, data, sizeof(data));
+
+ if (count < 0) {
+ warnx("read error");
+ return 1;
+ }
+
+ 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);
+ }
+
+ px4_close(fd);
+ return 0;
+}
+}
+
+int
+adc_main(int argc, char *argv[])
+{
+ int ret = 0;
+
+ if (g_adc == nullptr) {
+#ifdef CONFIG_ARCH_BOARD_LINUXTEST
+ /* XXX this hardcodes the default channel set for LINUXTEST - should be configurable */
+ g_adc = new ADCSIM((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
+#endif
+
+ if (g_adc == nullptr) {
+ warnx("couldn't allocate the ADCSIM driver");
+ return 1;
+ }
+
+ if (g_adc->init() != OK) {
+ delete g_adc;
+ warnx("ADCSIM init failed");
+ return 1;
+ }
+ }
+
+ if (argc > 1) {
+ if (!strcmp(argv[1], "test"))
+ ret = test();
+ }
+
+ return ret;
+}
diff --git a/src/platforms/linux/drivers/adcsim/module.mk b/src/platforms/linux/drivers/adcsim/module.mk
new file mode 100644
index 000000000..9b8461fd7
--- /dev/null
+++ b/src/platforms/linux/drivers/adcsim/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 = adcsim.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/platforms/px4_adc.h b/src/platforms/px4_adc.h
index 0b123ed0c..bda39d036 100644
--- a/src/platforms/px4_adc.h
+++ b/src/platforms/px4_adc.h
@@ -39,6 +39,8 @@
#pragma once
+#include <stdint.h>
+
#if defined(__PX4_ROS)
#error "ADC not supported in ROS"
#elif defined(__PX4_NUTTX)
@@ -54,13 +56,13 @@ struct adc_msg_s
{
uint8_t am_channel; /* The 8-bit ADC Channel */
int32_t am_data; /* ADC convert result (4 bytes) */
-} packed_struct;
+} __attribute__ ((packed));
// Example settings
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_BATTERY_CURRENT_CHANNEL -1
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
-
+#define ADCSIM0_DEVICE_PATH "/dev/adc0"
#else
#error "No target platform defined"
#endif