px4iofirmware delete unused i2c and hx_stream

This commit is contained in:
Daniel Agar 2019-11-21 13:48:05 -05:00
parent d82f9590c6
commit 284c9afe32
5 changed files with 1 additions and 846 deletions

View File

@ -35,7 +35,7 @@
* @file px4io.cpp
* Driver for the PX4IO board.
*
* PX4IO is connected via I2C or DMA enabled high-speed UART.
* PX4IO is connected via DMA enabled high-speed UART.
*/
#include <px4_platform_common/px4_config.h>

View File

@ -32,7 +32,6 @@
############################################################################
add_library(px4iofirmware
hx_stream.c
adc.c
controls.c
mixer.cpp

View File

@ -1,322 +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 hx_stream.c
*
* A simple serial line framing protocol based on HDLC
* with 32-bit CRC protection.
*/
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <crc32.h>
#include <unistd.h>
#include <errno.h>
#include <string.h>
#include <stdio.h>
#include <perf/perf_counter.h>
#include "hx_stream.h"
struct hx_stream {
/* RX state */
uint8_t rx_buf[HX_STREAM_MAX_FRAME + 4];
unsigned rx_frame_bytes;
bool rx_escaped;
hx_stream_rx_callback rx_callback;
void *rx_callback_arg;
/* TX state */
int fd;
bool tx_error;
const uint8_t *tx_buf;
unsigned tx_resid;
uint32_t tx_crc;
enum {
TX_IDLE = 0,
TX_SEND_START,
TX_SEND_DATA,
TX_SENT_ESCAPE,
TX_SEND_END
} tx_state;
perf_counter_t pc_tx_frames;
perf_counter_t pc_rx_frames;
perf_counter_t pc_rx_errors;
};
/*
* Protocol magic numbers, straight out of HDLC.
*/
#define FBO 0x7e /**< Frame Boundary Octet */
#define CEO 0x7c /**< Control Escape Octet */
static void hx_tx_raw(hx_stream_t stream, uint8_t c);
static void hx_tx_raw(hx_stream_t stream, uint8_t c);
static int hx_rx_frame(hx_stream_t stream);
static void
hx_tx_raw(hx_stream_t stream, uint8_t c)
{
if (write(stream->fd, &c, 1) != 1) {
stream->tx_error = true;
}
}
static int
hx_rx_frame(hx_stream_t stream)
{
union {
uint8_t b[4];
uint32_t w;
} u;
unsigned length = stream->rx_frame_bytes;
/* reset the stream */
stream->rx_frame_bytes = 0;
stream->rx_escaped = false;
/* not a real frame - too short */
if (length < 4) {
if (length > 1) {
perf_count(stream->pc_rx_errors);
}
return 0;
}
length -= 4;
/* compute expected CRC */
u.w = crc32(&stream->rx_buf[0], length);
/* compare computed and actual CRC */
for (unsigned i = 0; i < 4; i++) {
if (u.b[i] != stream->rx_buf[length + i]) {
perf_count(stream->pc_rx_errors);
return 0;
}
}
/* frame is good */
perf_count(stream->pc_rx_frames);
stream->rx_callback(stream->rx_callback_arg, &stream->rx_buf[0], length);
return 1;
}
hx_stream_t
hx_stream_init(int fd,
hx_stream_rx_callback callback,
void *arg)
{
hx_stream_t stream;
stream = (hx_stream_t)malloc(sizeof(struct hx_stream));
if (stream != NULL) {
memset(stream, 0, sizeof(struct hx_stream));
stream->fd = fd;
stream->rx_callback = callback;
stream->rx_callback_arg = arg;
}
return stream;
}
void
hx_stream_free(hx_stream_t stream)
{
/* free perf counters (OK if they are NULL) */
perf_free(stream->pc_tx_frames);
perf_free(stream->pc_rx_frames);
perf_free(stream->pc_rx_errors);
free(stream);
}
void
hx_stream_set_counters(hx_stream_t stream,
perf_counter_t tx_frames,
perf_counter_t rx_frames,
perf_counter_t rx_errors)
{
stream->pc_tx_frames = tx_frames;
stream->pc_rx_frames = rx_frames;
stream->pc_rx_errors = rx_errors;
}
void
hx_stream_reset(hx_stream_t stream)
{
stream->rx_frame_bytes = 0;
stream->rx_escaped = false;
stream->tx_buf = NULL;
stream->tx_resid = 0;
stream->tx_state = TX_IDLE;
}
int
hx_stream_start(hx_stream_t stream,
const void *data,
size_t count)
{
if (count > HX_STREAM_MAX_FRAME) {
return -EINVAL;
}
stream->tx_buf = data;
stream->tx_resid = count;
stream->tx_state = TX_SEND_START;
stream->tx_crc = crc32(data, count);
return OK;
}
int
hx_stream_send_next(hx_stream_t stream)
{
int c;
/* sort out what we're going to send */
switch (stream->tx_state) {
case TX_SEND_START:
stream->tx_state = TX_SEND_DATA;
return FBO;
case TX_SEND_DATA:
c = *stream->tx_buf;
switch (c) {
case FBO:
case CEO:
stream->tx_state = TX_SENT_ESCAPE;
return CEO;
}
break;
case TX_SENT_ESCAPE:
c = *stream->tx_buf ^ 0x20;
stream->tx_state = TX_SEND_DATA;
break;
case TX_SEND_END:
stream->tx_state = TX_IDLE;
return FBO;
case TX_IDLE:
default:
return -1;
}
/* if we are here, we have consumed a byte from the buffer */
stream->tx_resid--;
stream->tx_buf++;
/* buffer exhausted */
if (stream->tx_resid == 0) {
uint8_t *pcrc = (uint8_t *)&stream->tx_crc;
/* was the buffer the frame CRC? */
if (stream->tx_buf == (pcrc + sizeof(stream->tx_crc))) {
stream->tx_state = TX_SEND_END;
} else {
/* no, it was the payload - switch to sending the CRC */
stream->tx_buf = pcrc;
stream->tx_resid = sizeof(stream->tx_crc);
}
}
return c;
}
int
hx_stream_send(hx_stream_t stream,
const void *data,
size_t count)
{
int result;
result = hx_stream_start(stream, data, count);
if (result != OK) {
return result;
}
int c;
while ((c = hx_stream_send_next(stream)) >= 0) {
hx_tx_raw(stream, c);
}
/* check for transmit error */
if (stream->tx_error) {
stream->tx_error = false;
return -EIO;
}
perf_count(stream->pc_tx_frames);
return OK;
}
void
hx_stream_rx(hx_stream_t stream, uint8_t c)
{
/* frame end? */
if (c == FBO) {
hx_rx_frame(stream);
return;
}
/* escaped? */
if (stream->rx_escaped) {
stream->rx_escaped = false;
c ^= 0x20;
} else if (c == CEO) {
/* now rx_escaped, ignore the byte */
stream->rx_escaped = true;
return;
}
/* save for later */
if (stream->rx_frame_bytes < sizeof(stream->rx_buf)) {
stream->rx_buf[stream->rx_frame_bytes++] = c;
}
}

View File

@ -1,162 +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 hx_stream.h
*
* A simple serial line framing protocol based on HDLC
* with 32-bit CRC protection.
*/
#ifndef _SYSTEMLIB_HX_STREAM_H
#define _SYSTEMLIB_HX_STREAM_H
#include <sys/types.h>
#include <perf/perf_counter.h>
struct hx_stream;
typedef struct hx_stream *hx_stream_t;
#define HX_STREAM_MAX_FRAME 64
typedef void (* hx_stream_rx_callback)(void *arg, const void *data, size_t length);
__BEGIN_DECLS
/**
* Allocate a new hx_stream object.
*
* @param fd The file handle over which the protocol will
* communicate, or -1 if the protocol will use
* hx_stream_start/hx_stream_send_next.
* @param callback Called when a frame is received.
* @param callback_arg Passed to the callback.
* @return A handle to the stream, or NULL if memory could
* not be allocated.
*/
__EXPORT extern hx_stream_t hx_stream_init(int fd,
hx_stream_rx_callback callback,
void *arg);
/**
* Free a hx_stream object.
*
* @param stream A handle returned from hx_stream_init.
*/
__EXPORT extern void hx_stream_free(hx_stream_t stream);
/**
* Set performance counters for the stream.
*
* Any counter may be set to NULL to disable counting that datum.
*
* @param stream A handle returned from hx_stream_init.
* @param tx_frames Counter for transmitted frames.
* @param rx_frames Counter for received frames.
* @param rx_errors Counter for short and corrupt received frames.
*/
__EXPORT extern void hx_stream_set_counters(hx_stream_t stream,
perf_counter_t tx_frames,
perf_counter_t rx_frames,
perf_counter_t rx_errors);
/**
* Reset a stream.
*
* Forces the local stream state to idle.
*
* @param stream A handle returned from hx_stream_init.
*/
__EXPORT extern void hx_stream_reset(hx_stream_t stream);
/**
* Prepare to send a frame.
*
* Use this in conjunction with hx_stream_send_next to
* set the frame to be transmitted.
*
* Use hx_stream_send() to write to the stream fd directly.
*
* @param stream A handle returned from hx_stream_init.
* @param data Pointer to the data to send.
* @param count The number of bytes to send.
* @return Zero on success, -errno on error.
*/
__EXPORT extern int hx_stream_start(hx_stream_t stream,
const void *data,
size_t count);
/**
* Get the next byte to send for a stream.
*
* This requires that the stream be prepared for sending by
* calling hx_stream_start first.
*
* @param stream A handle returned from hx_stream_init.
* @return The byte to send, or -1 if there is
* nothing left to send.
*/
__EXPORT extern int hx_stream_send_next(hx_stream_t stream);
/**
* Send a frame.
*
* This function will block until all frame bytes are sent if
* the descriptor passed to hx_stream_init is marked blocking,
* otherwise it will return -1 (but may transmit a
* runt frame at the same time).
*
* @todo Handling of non-blocking streams needs to be better.
*
* @param stream A handle returned from hx_stream_init.
* @param data Pointer to the data to send.
* @param count The number of bytes to send.
* @return Zero on success, -errno on error.
*/
__EXPORT extern int hx_stream_send(hx_stream_t stream,
const void *data,
size_t count);
/**
* Handle a byte from the stream.
*
* @param stream A handle returned from hx_stream_init.
* @param c The character to process.
*/
__EXPORT extern void hx_stream_rx(hx_stream_t stream,
uint8_t c);
__END_DECLS
#endif

View File

@ -1,360 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* @file i2c.c
*
* I2C communication for the PX4IO module.
*/
#include <stdint.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include <stm32_i2c.h>
#include <stm32_dma.h>
//#define DEBUG
#include "px4io.h"
/*
* I2C register definitions.
*/
#define I2C_BASE STM32_I2C1_BASE
#define REG(_reg) (*(volatile uint32_t *)(I2C_BASE + _reg))
#define rCR1 REG(STM32_I2C_CR1_OFFSET)
#define rCR2 REG(STM32_I2C_CR2_OFFSET)
#define rOAR1 REG(STM32_I2C_OAR1_OFFSET)
#define rOAR2 REG(STM32_I2C_OAR2_OFFSET)
#define rDR REG(STM32_I2C_DR_OFFSET)
#define rSR1 REG(STM32_I2C_SR1_OFFSET)
#define rSR2 REG(STM32_I2C_SR2_OFFSET)
#define rCCR REG(STM32_I2C_CCR_OFFSET)
#define rTRISE REG(STM32_I2C_TRISE_OFFSET)
void i2c_reset(void);
static int i2c_interrupt(int irq, void *context, void *args);
static void i2c_rx_setup(void);
static void i2c_tx_setup(void);
static void i2c_rx_complete(void);
static void i2c_tx_complete(void);
#ifdef DEBUG
static void i2c_dump(void);
#endif
static DMA_HANDLE rx_dma;
static DMA_HANDLE tx_dma;
static uint8_t rx_buf[68];
static unsigned rx_len;
static const uint8_t junk_buf[] = { 0xff, 0xff, 0xff, 0xff };
static const uint8_t *tx_buf = junk_buf;
static unsigned tx_len = sizeof(junk_buf);
unsigned tx_count;
static uint8_t selected_page;
static uint8_t selected_offset;
enum {
DIR_NONE = 0,
DIR_TX = 1,
DIR_RX = 2
} direction;
void
interface_init(void)
{
debug("i2c init");
/* allocate DMA handles and initialise DMA */
rx_dma = stm32_dmachannel(DMACHAN_I2C1_RX);
i2c_rx_setup();
tx_dma = stm32_dmachannel(DMACHAN_I2C1_TX);
i2c_tx_setup();
/* enable the i2c block clock and reset it */
modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C1EN);
modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C1RST);
modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C1RST, 0);
/* configure the i2c GPIOs */
px4_arch_configgpio(GPIO_I2C1_SCL);
px4_arch_configgpio(GPIO_I2C1_SDA);
/* soft-reset the block */
rCR1 |= I2C_CR1_SWRST;
rCR1 = 0;
/* set for DMA operation */
rCR2 |= I2C_CR2_ITEVFEN | I2C_CR2_ITERREN | I2C_CR2_DMAEN;
/* set the frequency value in CR2 */
rCR2 &= ~I2C_CR2_FREQ_MASK;
rCR2 |= STM32_PCLK1_FREQUENCY / 1000000;
/* set divisor and risetime for fast mode */
uint16_t result = STM32_PCLK1_FREQUENCY / (400000 * 25);
if (result < 1) {
result = 1;
}
result = 3;
rCCR &= ~I2C_CCR_CCR_MASK;
rCCR |= I2C_CCR_DUTY | I2C_CCR_FS | result;
rTRISE = (uint16_t)((((STM32_PCLK1_FREQUENCY / 1000000) * 300) / 1000) + 1);
/* set our device address */
rOAR1 = 0x1a << 1;
/* enable event interrupts */
irq_attach(STM32_IRQ_I2C1EV, i2c_interrupt, NULL);
irq_attach(STM32_IRQ_I2C1ER, i2c_interrupt, NULL);
up_enable_irq(STM32_IRQ_I2C1EV);
up_enable_irq(STM32_IRQ_I2C1ER);
/* and enable the I2C port */
rCR1 |= I2C_CR1_ACK | I2C_CR1_PE;
#ifdef DEBUG
i2c_dump();
#endif
}
/*
reset the I2C bus
used to recover from lockups
*/
void
i2c_reset(void)
{
rCR1 |= I2C_CR1_SWRST;
rCR1 = 0;
/* set for DMA operation */
rCR2 |= I2C_CR2_ITEVFEN | I2C_CR2_ITERREN | I2C_CR2_DMAEN;
/* set the frequency value in CR2 */
rCR2 &= ~I2C_CR2_FREQ_MASK;
rCR2 |= STM32_PCLK1_FREQUENCY / 1000000;
/* set divisor and risetime for fast mode */
uint16_t result = STM32_PCLK1_FREQUENCY / (400000 * 25);
if (result < 1) {
result = 1;
}
result = 3;
rCCR &= ~I2C_CCR_CCR_MASK;
rCCR |= I2C_CCR_DUTY | I2C_CCR_FS | result;
rTRISE = (uint16_t)((((STM32_PCLK1_FREQUENCY / 1000000) * 300) / 1000) + 1);
/* set our device address */
rOAR1 = 0x1a << 1;
/* and enable the I2C port */
rCR1 |= I2C_CR1_ACK | I2C_CR1_PE;
}
static int
i2c_interrupt(int irq, FAR void *context, FAR void *args)
{
uint16_t sr1 = rSR1;
if (sr1 & (I2C_SR1_STOPF | I2C_SR1_AF | I2C_SR1_ADDR)) {
if (sr1 & I2C_SR1_STOPF) {
/* write to CR1 to clear STOPF */
(void)rSR1; /* as recommended, re-read SR1 */
rCR1 |= I2C_CR1_PE;
}
/* DMA never stops, so we should do that now */
switch (direction) {
case DIR_TX:
i2c_tx_complete();
break;
case DIR_RX:
i2c_rx_complete();
break;
default:
/* not currently transferring - must be a new txn */
break;
}
direction = DIR_NONE;
}
if (sr1 & I2C_SR1_ADDR) {
/* clear ADDR to ack our selection and get direction */
(void)rSR1; /* as recommended, re-read SR1 */
uint16_t sr2 = rSR2;
if (sr2 & I2C_SR2_TRA) {
/* we are the transmitter */
direction = DIR_TX;
} else {
/* we are the receiver */
direction = DIR_RX;
}
}
/* clear any errors that might need it (this handles AF as well */
if (sr1 & I2C_SR1_ERRORMASK) {
rSR1 = 0;
}
return 0;
}
static void
i2c_rx_setup(void)
{
/*
* Note that we configure DMA in circular mode; this means that a too-long
* transfer will overwrite the buffer, but that avoids us having to deal with
* bailing out of a transaction while the master is still babbling at us.
*/
rx_len = 0;
stm32_dmasetup(rx_dma, (uintptr_t)&rDR, (uintptr_t)&rx_buf[0], sizeof(rx_buf),
DMA_CCR_CIRC |
DMA_CCR_MINC |
DMA_CCR_PSIZE_32BITS |
DMA_CCR_MSIZE_8BITS |
DMA_CCR_PRIMED);
stm32_dmastart(rx_dma, NULL, NULL, false);
}
static void
i2c_rx_complete(void)
{
rx_len = sizeof(rx_buf) - stm32_dmaresidual(rx_dma);
stm32_dmastop(rx_dma);
if (rx_len >= 2) {
selected_page = rx_buf[0];
selected_offset = rx_buf[1];
/* work out how many registers are being written */
unsigned count = (rx_len - 2) / 2;
if (count > 0) {
registers_set(selected_page, selected_offset, (const uint16_t *)&rx_buf[2], count);
} else {
/* no registers written, must be an address cycle */
uint16_t *regs;
unsigned reg_count;
/* work out which registers are being addressed */
int ret = registers_get(selected_page, selected_offset, &regs, &reg_count);
if (ret == 0) {
tx_buf = (uint8_t *)regs;
tx_len = reg_count * 2;
} else {
tx_buf = junk_buf;
tx_len = sizeof(junk_buf);
}
/* disable interrupts while reconfiguring DMA for the selected registers */
irqstate_t flags = px4_enter_critical_section();
stm32_dmastop(tx_dma);
i2c_tx_setup();
px4_leave_critical_section(flags);
}
}
/* prepare for the next transaction */
i2c_rx_setup();
}
static void
i2c_tx_setup(void)
{
/*
* Note that we configure DMA in circular mode; this means that a too-long
* transfer will copy the buffer more than once, but that avoids us having
* to deal with bailing out of a transaction while the master is still
* babbling at us.
*/
stm32_dmasetup(tx_dma, (uintptr_t)&rDR, (uintptr_t)&tx_buf[0], tx_len,
DMA_CCR_DIR |
DMA_CCR_CIRC |
DMA_CCR_MINC |
DMA_CCR_PSIZE_8BITS |
DMA_CCR_MSIZE_8BITS |
DMA_CCR_PRIMED);
stm32_dmastart(tx_dma, NULL, NULL, false);
}
static void
i2c_tx_complete(void)
{
tx_count = tx_len - stm32_dmaresidual(tx_dma);
stm32_dmastop(tx_dma);
/* for debug purposes, save the length of the last transmit as seen by the DMA */
/* leave tx_buf/tx_len alone, so that a retry will see the same data */
/* prepare for the next transaction */
i2c_tx_setup();
}
#ifdef DEBUG
static void
i2c_dump(void)
{
debug("CR1 0x%08x CR2 0x%08x", rCR1, rCR2);
debug("OAR1 0x%08x OAR2 0x%08x", rOAR1, rOAR2);
debug("CCR 0x%08x TRISE 0x%08x", rCCR, rTRISE);
debug("SR1 0x%08x SR2 0x%08x", rSR1, rSR2);
}
#endif