aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-08-05 20:11:44 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-08-05 20:11:44 +0200
commit86e5d39b89a95ba81cfbbadc22a5ebc03f068509 (patch)
treedb65deb9e716dee3272c8d045ca9d8567d70e23a /src/drivers
parentcac4a6f5789ce4fff8ba0f697777b6d59e0fb068 (diff)
parent901a9c3e35456445465e7008d3c69b0bd3481e9e (diff)
downloadpx4-firmware-86e5d39b89a95ba81cfbbadc22a5ebc03f068509.tar.gz
px4-firmware-86e5d39b89a95ba81cfbbadc22a5ebc03f068509.tar.bz2
px4-firmware-86e5d39b89a95ba81cfbbadc22a5ebc03f068509.zip
Merge branch 'master' of github.com:PX4/Firmware into mpu6k_queue
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/device/cdev.cpp16
-rw-r--r--src/drivers/device/device.cpp19
-rw-r--r--src/drivers/device/device.h70
-rw-r--r--src/drivers/device/i2c.h14
-rw-r--r--src/drivers/device/spi.h2
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp34
-rw-r--r--src/drivers/stm32/drv_pwm_servo.c6
7 files changed, 118 insertions, 43 deletions
diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp
index 422321850..47ebcd40a 100644
--- a/src/drivers/device/cdev.cpp
+++ b/src/drivers/device/cdev.cpp
@@ -111,21 +111,21 @@ CDev::~CDev()
int
CDev::init()
{
- int ret = OK;
-
// base class init first
- ret = Device::init();
+ int ret = Device::init();
if (ret != OK)
goto out;
// now register the driver
- ret = register_driver(_devname, &fops, 0666, (void *)this);
+ if (_devname != nullptr) {
+ ret = register_driver(_devname, &fops, 0666, (void *)this);
- if (ret != OK)
- goto out;
+ if (ret != OK)
+ goto out;
- _registered = true;
+ _registered = true;
+ }
out:
return ret;
@@ -395,4 +395,4 @@ cdev_poll(struct file *filp, struct pollfd *fds, bool setup)
return cdev->poll(filp, fds, setup);
}
-} // namespace device \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp
index 04a5222c3..c3ee77b1c 100644
--- a/src/drivers/device/device.cpp
+++ b/src/drivers/device/device.cpp
@@ -223,5 +223,22 @@ interrupt(int irq, void *context)
return OK;
}
+int
+Device::read(unsigned offset, void *data, unsigned count)
+{
+ return -ENODEV;
+}
+
+int
+Device::write(unsigned offset, void *data, unsigned count)
+{
+ return -ENODEV;
+}
+
+int
+Device::ioctl(unsigned operation, unsigned &arg)
+{
+ return -ENODEV;
+}
-} // namespace device \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h
index 7d375aab9..a9ed5d77c 100644
--- a/src/drivers/device/device.h
+++ b/src/drivers/device/device.h
@@ -69,10 +69,61 @@ class __EXPORT Device
{
public:
/**
+ * Destructor.
+ *
+ * Public so that anonymous devices can be destroyed.
+ */
+ virtual ~Device();
+
+ /**
* Interrupt handler.
*/
virtual void interrupt(void *ctx); /**< interrupt handler */
+ /*
+ * Direct access methods.
+ */
+
+ /**
+ * Initialise the driver and make it ready for use.
+ *
+ * @return OK if the driver initialized OK, negative errno otherwise;
+ */
+ virtual int init();
+
+ /**
+ * Read directly from the device.
+ *
+ * The actual size of each unit quantity is device-specific.
+ *
+ * @param offset The device address at which to start reading
+ * @param data The buffer into which the read values should be placed.
+ * @param count The number of items to read.
+ * @return The number of items read on success, negative errno otherwise.
+ */
+ virtual int read(unsigned address, void *data, unsigned count);
+
+ /**
+ * Write directly to the device.
+ *
+ * The actual size of each unit quantity is device-specific.
+ *
+ * @param address The device address at which to start writing.
+ * @param data The buffer from which values should be read.
+ * @param count The number of items to write.
+ * @return The number of items written on success, negative errno otherwise.
+ */
+ virtual int write(unsigned address, void *data, unsigned count);
+
+ /**
+ * Perform a device-specific operation.
+ *
+ * @param operation The operation to perform.
+ * @param arg An argument to the operation.
+ * @return Negative errno on error, OK or positive value on success.
+ */
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
protected:
const char *_name; /**< driver name */
bool _debug_enabled; /**< if true, debug messages are printed */
@@ -85,14 +136,6 @@ protected:
*/
Device(const char *name,
int irq = 0);
- ~Device();
-
- /**
- * Initialise the driver and make it ready for use.
- *
- * @return OK if the driver initialised OK.
- */
- virtual int init();
/**
* Enable the device interrupt
@@ -189,7 +232,7 @@ public:
/**
* Destructor
*/
- ~CDev();
+ virtual ~CDev();
virtual int init();
@@ -282,6 +325,7 @@ public:
* Test whether the device is currently open.
*
* This can be used to avoid tearing down a device that is still active.
+ * Note - not virtual, cannot be overridden by a subclass.
*
* @return True if the device is currently open.
*/
@@ -396,9 +440,9 @@ public:
const char *devname,
uint32_t base,
int irq = 0);
- ~PIO();
+ virtual ~PIO();
- int init();
+ virtual int init();
protected:
@@ -407,7 +451,7 @@ protected:
*
* @param offset Register offset in bytes from the base address.
*/
- uint32_t reg(uint32_t offset) {
+ uint32_t reg(uint32_t offset) {
return *(volatile uint32_t *)(_base + offset);
}
@@ -444,4 +488,4 @@ private:
} // namespace device
-#endif /* _DEVICE_DEVICE_H */ \ No newline at end of file
+#endif /* _DEVICE_DEVICE_H */
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index b4a9cdd53..549879352 100644
--- a/src/drivers/device/i2c.h
+++ b/src/drivers/device/i2c.h
@@ -55,13 +55,11 @@ class __EXPORT I2C : public CDev
public:
- /**
- * Get the address
- */
- uint16_t get_address() {
- return _address;
- }
-
+ /**
+ * Get the address
+ */
+ int16_t get_address() { return _address; }
+
protected:
/**
* The number of times a read or write operation will be retried on
@@ -90,7 +88,7 @@ protected:
uint16_t address,
uint32_t frequency,
int irq = 0);
- ~I2C();
+ virtual ~I2C();
virtual int init();
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index d2d01efb3..e0122372a 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -71,7 +71,7 @@ protected:
enum spi_mode_e mode,
uint32_t frequency,
int irq = 0);
- ~SPI();
+ virtual ~SPI();
virtual int init();
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index 7a2e22c01..ebae21cf7 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -34,6 +34,7 @@
/**
* @file meas_airspeed.cpp
* @author Lorenz Meier
+ * @author Sarthak Kaingade
* @author Simon Wilks
*
* Driver for the MEAS Spec series connected via I2C.
@@ -92,9 +93,6 @@
/* Register address */
#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
-#define ADDR_READ_DF2 0x00 /* read from this address to read pressure only */
-#define ADDR_READ_DF3 0x01
-#define ADDR_READ_DF4 0x02 /* read from this address to read pressure and temp */
/* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
@@ -122,7 +120,7 @@ protected:
extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]);
MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address,
- CONVERSION_INTERVAL)
+ CONVERSION_INTERVAL)
{
}
@@ -160,7 +158,7 @@ MEASAirspeed::collect()
perf_begin(_sample_perf);
- ret = transfer(nullptr, 0, &val[0], 2);
+ ret = transfer(nullptr, 0, &val[0], 4);
if (ret < 0) {
log("error reading from sensor: %d", ret);
@@ -171,25 +169,37 @@ MEASAirspeed::collect()
if (status == 2) {
log("err: stale data");
+
} else if (status == 3) {
log("err: fault");
}
- uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8);
+ //uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8);
uint16_t temp = (val[3] & 0xE0) << 8 | val[2];
- diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f));
- diff_pres_pa -= _diff_pres_offset;
+ // XXX leaving this in until new calculation method has been cross-checked
+ //diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f));
+ //diff_pres_pa -= _diff_pres_offset;
+ int16_t dp_raw = 0, dT_raw = 0;
+ dp_raw = (val[0] << 8) + val[1];
+ dp_raw = 0x3FFF & dp_raw;
+ dT_raw = (val[2] << 8) + val[3];
+ dT_raw = (0xFFE0 & dT_raw) >> 5;
+ float temperature = ((200 * dT_raw) / 2047) - 50;
// XXX we may want to smooth out the readings to remove noise.
+ // Calculate differential pressure. As its centered around 8000
+ // and can go positive or negative, enforce absolute value
+ uint16_t diff_press_pa = abs(dp_raw - (16384 / 2.0f));
+
_reports[_next_report].timestamp = hrt_absolute_time();
- _reports[_next_report].temperature = temp;
- _reports[_next_report].differential_pressure_pa = diff_pres_pa;
+ _reports[_next_report].temperature = temperature;
+ _reports[_next_report].differential_pressure_pa = diff_press_pa;
// Track maximum differential pressure measured (so we can work out top speed).
- if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) {
- _reports[_next_report].max_differential_pressure_pa = diff_pres_pa;
+ if (diff_press_pa > _reports[_next_report].max_differential_pressure_pa) {
+ _reports[_next_report].max_differential_pressure_pa = diff_press_pa;
}
/* announce the airspeed if needed, just publish else */
diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c
index 7b060412c..dbb45a138 100644
--- a/src/drivers/stm32/drv_pwm_servo.c
+++ b/src/drivers/stm32/drv_pwm_servo.c
@@ -88,6 +88,7 @@
#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
+#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
static void pwm_timer_init(unsigned timer);
static void pwm_timer_set_rate(unsigned timer, unsigned rate);
@@ -110,6 +111,11 @@ pwm_timer_init(unsigned timer)
rCCER(timer) = 0;
rDCR(timer) = 0;
+ if ((pwm_timers[timer].base == STM32_TIM1_BASE) || (pwm_timers[timer].base == STM32_TIM8_BASE)) {
+ /* master output enable = on */
+ rBDTR(timer) = ATIM_BDTR_MOE;
+ }
+
/* configure the timer to free-run at 1MHz */
rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1;