aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-07-14 11:44:46 -0700
committerpx4dev <px4@purgatory.org>2013-07-14 11:44:46 -0700
commit6c7f1e883e0e0e8f09618ba1a80075f39faadf0b (patch)
treea37ca8406b330646bf46e258fdd6b24a29befc96 /src/drivers
parent12b84597d8058412002de6292d5def559b19c7e6 (diff)
downloadpx4-firmware-6c7f1e883e0e0e8f09618ba1a80075f39faadf0b.tar.gz
px4-firmware-6c7f1e883e0e0e8f09618ba1a80075f39faadf0b.tar.bz2
px4-firmware-6c7f1e883e0e0e8f09618ba1a80075f39faadf0b.zip
Direct-access device functions return errors directly.
Move to using ::init rather than ::probe in keeping with device changes.
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/px4io/interface.h85
-rw-r--r--src/drivers/px4io/px4io.cpp12
-rw-r--r--src/drivers/px4io/px4io_i2c.cpp25
-rw-r--r--src/drivers/px4io/px4io_serial.cpp113
4 files changed, 79 insertions, 156 deletions
diff --git a/src/drivers/px4io/interface.h b/src/drivers/px4io/interface.h
deleted file mode 100644
index cb7da1081..000000000
--- a/src/drivers/px4io/interface.h
+++ /dev/null
@@ -1,85 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 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.
- *
- ****************************************************************************/
-
-/**
- * @file interface.h
- *
- * PX4IO interface classes.
- */
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-
-class PX4IO_interface
-{
-public:
- /**
- * Check that the interface initialised OK.
- *
- * Does not check that communication has been established.
- */
- virtual bool ok() = 0;
-
- /**
- * Set PX4IO registers.
- *
- * @param page The register page to write
- * @param offset Offset of the first register to write
- * @param values Pointer to values to write
- * @param num_values The number of values to write
- * @return Zero on success.
- */
- virtual int set_reg(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values) = 0;
-
- /**
- * Get PX4IO registers.
- *
- * @param page The register page to read
- * @param offset Offset of the first register to read
- * @param values Pointer to store values read
- * @param num_values The number of values to read
- * @return Zero on success.
- */
- virtual int get_reg(uint8_t page, uint8_t offset, uint16_t *values, unsigned num_values) = 0;
-
- /**
- * Perform an interface test.
- *
- * @param mode Optional test mode.
- */
- virtual int test(unsigned mode) = 0;
-};
-
-extern PX4IO_interface *io_i2c_interface(int bus, uint8_t address);
-extern PX4IO_interface *io_serial_interface();
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 1b4f20de0..904da84c4 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -1132,8 +1132,8 @@ PX4IO::io_reg_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned
}
int ret = _interface->write((page << 8) | offset, (void *)values, num_values);
- if (ret != OK)
- debug("io_reg_set(%u,%u,%u): error %d", page, offset, num_values, errno);
+ if (ret != num_values)
+ debug("io_reg_set(%u,%u,%u): error %d", page, offset, num_values, ret);
return ret;
}
@@ -1153,8 +1153,8 @@ PX4IO::io_reg_get(uint8_t page, uint8_t offset, uint16_t *values, unsigned num_v
}
int ret = _interface->read((page << 8) | offset, reinterpret_cast<void *>(values), num_values);
- if (ret != OK)
- debug("io_reg_get(%u,%u,%u): data error %d", page, offset, num_values, errno);
+ if (ret != num_values)
+ debug("io_reg_get(%u,%u,%u): data error %d", page, offset, num_values, ret);
return ret;
}
@@ -1617,7 +1617,7 @@ start(int argc, char *argv[])
if (interface == nullptr)
errx(1, "cannot alloc interface");
- if (interface->probe()) {
+ if (interface->init()) {
delete interface;
errx(1, "interface init failed");
}
@@ -1754,7 +1754,7 @@ if_test(unsigned mode)
if (interface == nullptr)
errx(1, "cannot alloc interface");
- if (interface->probe()) {
+ if (interface->init()) {
delete interface;
errx(1, "interface init failed");
} else {
diff --git a/src/drivers/px4io/px4io_i2c.cpp b/src/drivers/px4io/px4io_i2c.cpp
index 317326e40..585b995fe 100644
--- a/src/drivers/px4io/px4io_i2c.cpp
+++ b/src/drivers/px4io/px4io_i2c.cpp
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file interface_i2c.cpp
+ * @file px4io_i2c.cpp
*
* I2C interface for PX4IO
*/
@@ -65,7 +65,7 @@ public:
PX4IO_I2C(int bus, uint8_t address);
virtual ~PX4IO_I2C();
- virtual int probe();
+ virtual int init();
virtual int read(unsigned offset, void *data, unsigned count = 1);
virtual int write(unsigned address, void *data, unsigned count = 1);
virtual int ioctl(unsigned operation, unsigned &arg);
@@ -94,10 +94,17 @@ PX4IO_I2C::~PX4IO_I2C()
}
int
-PX4IO_I2C::probe()
+PX4IO_I2C::init()
{
- /* XXX really should do something here */
+ int ret;
+ ret = I2C::init();
+ if (ret != OK)
+ goto out;
+
+ /* XXX really should do something more here */
+
+out:
return 0;
}
@@ -130,7 +137,10 @@ PX4IO_I2C::write(unsigned address, void *data, unsigned count)
msgv[1].buffer = (uint8_t *)values;
msgv[1].length = 2 * count;
- return transfer(msgv, 2);
+ int ret = transfer(msgv, 2);
+ if (ret == OK)
+ ret = count;
+ return ret;
}
int
@@ -155,5 +165,8 @@ PX4IO_I2C::read(unsigned address, void *data, unsigned count)
msgv[1].buffer = (uint8_t *)values;
msgv[1].length = 2 * count;
- return transfer(msgv, 2);
+ int ret = transfer(msgv, 2);
+ if (ret == OK)
+ ret = count;
+ return ret;
}
diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp
index 20b89accb..6a0b4d33f 100644
--- a/src/drivers/px4io/px4io_serial.cpp
+++ b/src/drivers/px4io/px4io_serial.cpp
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file interface_serial.cpp
+ * @file px4io_serial.cpp
*
* Serial interface for PX4IO
*/
@@ -85,7 +85,7 @@ public:
PX4IO_serial();
virtual ~PX4IO_serial();
- virtual int probe();
+ virtual int init();
virtual int read(unsigned offset, void *data, unsigned count = 1);
virtual int write(unsigned address, void *data, unsigned count = 1);
virtual int ioctl(unsigned operation, unsigned &arg);
@@ -181,43 +181,6 @@ PX4IO_serial::PX4IO_serial() :
_pc_idle(perf_alloc(PC_COUNT, "io_idle ")),
_pc_badidle(perf_alloc(PC_COUNT, "io_badidle "))
{
- /* allocate DMA */
- _tx_dma = stm32_dmachannel(PX4IO_SERIAL_TX_DMAMAP);
- _rx_dma = stm32_dmachannel(PX4IO_SERIAL_RX_DMAMAP);
- if ((_tx_dma == nullptr) || (_rx_dma == nullptr))
- return;
-
- /* configure pins for serial use */
- stm32_configgpio(PX4IO_SERIAL_TX_GPIO);
- stm32_configgpio(PX4IO_SERIAL_RX_GPIO);
-
- /* reset & configure the UART */
- rCR1 = 0;
- rCR2 = 0;
- rCR3 = 0;
-
- /* eat any existing interrupt status */
- (void)rSR;
- (void)rDR;
-
- /* configure line speed */
- uint32_t usartdiv32 = PX4IO_SERIAL_CLOCK / (PX4IO_SERIAL_BITRATE / 2);
- uint32_t mantissa = usartdiv32 >> 5;
- uint32_t fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
- rBRR = (mantissa << USART_BRR_MANT_SHIFT) | (fraction << USART_BRR_FRAC_SHIFT);
-
- /* attach serial interrupt handler */
- irq_attach(PX4IO_SERIAL_VECTOR, _interrupt);
- up_enable_irq(PX4IO_SERIAL_VECTOR);
-
- /* enable UART in DMA mode, enable error and line idle interrupts */
- /* rCR3 = USART_CR3_EIE;*/
- rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE;
-
- /* create semaphores */
- sem_init(&_completion_semaphore, 0, 0);
- sem_init(&_bus_semaphore, 0, 1);
-
g_interface = this;
}
@@ -265,15 +228,48 @@ PX4IO_serial::~PX4IO_serial()
}
int
-PX4IO_serial::probe()
+PX4IO_serial::init()
{
- /* XXX this could try talking to IO */
-
- if (_tx_dma == nullptr)
- return -1;
- if (_rx_dma == nullptr)
+ /* allocate DMA */
+ _tx_dma = stm32_dmachannel(PX4IO_SERIAL_TX_DMAMAP);
+ _rx_dma = stm32_dmachannel(PX4IO_SERIAL_RX_DMAMAP);
+ if ((_tx_dma == nullptr) || (_rx_dma == nullptr))
return -1;
+ /* configure pins for serial use */
+ stm32_configgpio(PX4IO_SERIAL_TX_GPIO);
+ stm32_configgpio(PX4IO_SERIAL_RX_GPIO);
+
+ /* reset & configure the UART */
+ rCR1 = 0;
+ rCR2 = 0;
+ rCR3 = 0;
+
+ /* eat any existing interrupt status */
+ (void)rSR;
+ (void)rDR;
+
+ /* configure line speed */
+ uint32_t usartdiv32 = PX4IO_SERIAL_CLOCK / (PX4IO_SERIAL_BITRATE / 2);
+ uint32_t mantissa = usartdiv32 >> 5;
+ uint32_t fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
+ rBRR = (mantissa << USART_BRR_MANT_SHIFT) | (fraction << USART_BRR_FRAC_SHIFT);
+
+ /* attach serial interrupt handler */
+ irq_attach(PX4IO_SERIAL_VECTOR, _interrupt);
+ up_enable_irq(PX4IO_SERIAL_VECTOR);
+
+ /* enable UART in DMA mode, enable error and line idle interrupts */
+ /* rCR3 = USART_CR3_EIE;*/
+ rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE;
+
+ /* create semaphores */
+ sem_init(&_completion_semaphore, 0, 0);
+ sem_init(&_bus_semaphore, 0, 1);
+
+
+ /* XXX this could try talking to IO */
+
return 0;
}
@@ -344,10 +340,8 @@ PX4IO_serial::write(unsigned address, void *data, unsigned count)
uint8_t offset = address & 0xff;
const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
- if (count > PKT_MAX_REGS) {
- errno = EINVAL;
- return -1;
- }
+ if (count > PKT_MAX_REGS)
+ return -EINVAL;
sem_wait(&_bus_semaphore);
@@ -373,8 +367,7 @@ PX4IO_serial::write(unsigned address, void *data, unsigned count)
if (PKT_CODE(_dma_buffer) == PKT_CODE_ERROR) {
/* IO didn't like it - no point retrying */
- errno = EINVAL;
- result = -1;
+ result = -EINVAL;
perf_count(_pc_protoerrs);
}
@@ -384,6 +377,9 @@ PX4IO_serial::write(unsigned address, void *data, unsigned count)
}
sem_post(&_bus_semaphore);
+
+ if (result == OK)
+ result = count;
return result;
}
@@ -416,16 +412,14 @@ PX4IO_serial::read(unsigned address, void *data, unsigned count)
if (PKT_CODE(_dma_buffer) == PKT_CODE_ERROR) {
/* IO didn't like it - no point retrying */
- errno = EINVAL;
- result = -1;
+ result = -EINVAL;
perf_count(_pc_protoerrs);
/* compare the received count with the expected count */
} else if (PKT_COUNT(_dma_buffer) != count) {
/* IO returned the wrong number of registers - no point retrying */
- errno = EIO;
- result = -1;
+ result = -EIO;
perf_count(_pc_protoerrs);
/* successful read */
@@ -441,6 +435,9 @@ PX4IO_serial::read(unsigned address, void *data, unsigned count)
}
sem_post(&_bus_semaphore);
+
+ if (result == OK)
+ result = count;
return result;
}
@@ -524,8 +521,7 @@ PX4IO_serial::_wait_complete()
/* check for DMA errors */
if (_rx_dma_status & DMA_STATUS_TEIF) {
perf_count(_pc_dmaerrs);
- ret = -1;
- errno = EIO;
+ ret = -EIO;
break;
}
@@ -534,8 +530,7 @@ PX4IO_serial::_wait_complete()
_dma_buffer.crc = 0;
if ((crc != crc_packet(&_dma_buffer)) | (PKT_CODE(_dma_buffer) == PKT_CODE_CORRUPT)) {
perf_count(_pc_crcerrs);
- ret = -1;
- errno = EIO;
+ ret = -EIO;
break;
}