46 #include <nuttx/arch.h> 47 #include <arch/board/board.h> 51 #include <up_internal.h> 80 #define REG(_x) (*(volatile uint32_t *)(PX4FMU_SERIAL_BASE + _x)) 81 #define rSR REG(STM32_USART_SR_OFFSET) 82 #define rDR REG(STM32_USART_DR_OFFSET) 83 #define rBRR REG(STM32_USART_BRR_OFFSET) 84 #define rCR1 REG(STM32_USART_CR1_OFFSET) 85 #define rCR2 REG(STM32_USART_CR2_OFFSET) 86 #define rCR3 REG(STM32_USART_CR3_OFFSET) 87 #define rGTPR REG(STM32_USART_GTPR_OFFSET) 103 tx_dma = stm32_dmachannel(PX4FMU_SERIAL_TX_DMA);
104 rx_dma = stm32_dmachannel(PX4FMU_SERIAL_RX_DMA);
107 px4_arch_configgpio(PX4FMU_SERIAL_TX_GPIO);
108 px4_arch_configgpio(PX4FMU_SERIAL_RX_GPIO);
120 uint32_t usartdiv32 = PX4FMU_SERIAL_CLOCK / (PX4FMU_SERIAL_BITRATE / 2);
121 uint32_t mantissa = usartdiv32 >> 5;
122 uint32_t fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
123 rBRR = (mantissa << USART_BRR_MANT_SHIFT) | (fraction << USART_BRR_FRAC_SHIFT);
127 up_enable_irq(PX4FMU_SERIAL_VECTOR);
130 rCR3 = USART_CR3_EIE;
131 rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE;
136 while (!(
rSR & USART_SR_TXE))
141 while (!(
rSR & USART_SR_TXE))
152 debug(
"serial init");
231 rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
249 DMA_CCR_PSIZE_8BITS |
250 DMA_CCR_MSIZE_8BITS);
251 stm32_dmastart(
tx_dma, NULL, NULL,
false);
252 rCR3 |= USART_CR3_DMAT;
260 static bool abort_on_idle =
false;
265 if (sr & (USART_SR_ORE |
271 if (sr & USART_SR_ORE) {
275 if (sr & USART_SR_NE) {
279 if (sr & USART_SR_FE) {
284 rCR1 |= USART_CR1_SBK;
287 abort_on_idle =
true;
290 if (sr & USART_SR_IDLE) {
299 abort_on_idle =
false;
334 rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
350 DMA_CCR_PSIZE_8BITS |
351 DMA_CCR_MSIZE_8BITS |
356 rCR3 |= USART_CR3_DMAR;
static struct IOPacket dma_packet
static struct vehicle_status_s status
measure the time elapsed performing an event
static int serial_interrupt(int irq, void *context, FAR void *arg)
#define debug(fmt, args...)
static perf_counter_t pc_ne
static perf_counter_t pc_badidle
static perf_counter_t pc_fe
count the number of times an event occurs
static perf_counter_t pc_ore
static perf_counter_t pc_regerr
static perf_counter_t pc_txns
void interface_init(void)
FMU communications.
static perf_counter_t pc_idle
void perf_count(perf_counter_t handle)
Count a performance event.
static void rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
static void rx_handle_packet(void)
static uint8_t crc_packet(struct IOPacket *pkt) __attribute__((unused))
int registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_values)
uint16_t regs[PKT_MAX_REGS]
void perf_end(perf_counter_t handle)
End a performance event.
#define PKT_MAX_REGS
Serial protocol encapsulation.
static perf_counter_t pc_crcerr
General defines and structures for the PX4IO module firmware.
int registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
Register space.
void perf_begin(perf_counter_t handle)
Begin a performance event.
static perf_counter_t pc_errors
static void dma_reset(void)
Performance measuring tools.