PX4 Firmware
PX4 Autopilot Software http://px4.io
serial.c File Reference

Serial communication for the PX4IO module. More...

#include <stdint.h>
#include <unistd.h>
#include <termios.h>
#include <fcntl.h>
#include <string.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include <chip.h>
#include <up_internal.h>
#include <up_arch.h>
#include <stm32.h>
#include <perf/perf_counter.h>
#include "px4io.h"
Include dependency graph for serial.c:

Go to the source code of this file.

Macros

#define REG(_x)   (*(volatile uint32_t *)(PX4FMU_SERIAL_BASE + _x))
 
#define rSR   REG(STM32_USART_SR_OFFSET)
 
#define rDR   REG(STM32_USART_DR_OFFSET)
 
#define rBRR   REG(STM32_USART_BRR_OFFSET)
 
#define rCR1   REG(STM32_USART_CR1_OFFSET)
 
#define rCR2   REG(STM32_USART_CR2_OFFSET)
 
#define rCR3   REG(STM32_USART_CR3_OFFSET)
 
#define rGTPR   REG(STM32_USART_GTPR_OFFSET)
 

Functions

static void rx_handle_packet (void)
 
static void rx_dma_callback (DMA_HANDLE handle, uint8_t status, void *arg)
 
static int serial_interrupt (int irq, void *context, FAR void *arg)
 
static void dma_reset (void)
 
void interface_init (void)
 FMU communications. More...
 

Variables

static perf_counter_t pc_txns
 
static perf_counter_t pc_errors
 
static perf_counter_t pc_ore
 
static perf_counter_t pc_fe
 
static perf_counter_t pc_ne
 
static perf_counter_t pc_idle
 
static perf_counter_t pc_badidle
 
static perf_counter_t pc_regerr
 
static perf_counter_t pc_crcerr
 
static DMA_HANDLE tx_dma
 
static DMA_HANDLE rx_dma
 
static struct IOPacket dma_packet
 

Detailed Description

Serial communication for the PX4IO module.

Definition in file serial.c.

Macro Definition Documentation

◆ rBRR

#define rBRR   REG(STM32_USART_BRR_OFFSET)

Definition at line 83 of file serial.c.

Referenced by interface_init().

◆ rCR1

#define rCR1   REG(STM32_USART_CR1_OFFSET)

Definition at line 84 of file serial.c.

Referenced by interface_init(), and serial_interrupt().

◆ rCR2

#define rCR2   REG(STM32_USART_CR2_OFFSET)

Definition at line 85 of file serial.c.

Referenced by interface_init().

◆ rCR3

#define rCR3   REG(STM32_USART_CR3_OFFSET)

Definition at line 86 of file serial.c.

Referenced by dma_reset(), interface_init(), and rx_dma_callback().

◆ rDR

#define rDR   REG(STM32_USART_DR_OFFSET)

Definition at line 82 of file serial.c.

Referenced by dma_reset(), interface_init(), rx_dma_callback(), and serial_interrupt().

◆ REG

#define REG (   _x)    (*(volatile uint32_t *)(PX4FMU_SERIAL_BASE + _x))

Definition at line 80 of file serial.c.

◆ rGTPR

#define rGTPR   REG(STM32_USART_GTPR_OFFSET)

Definition at line 87 of file serial.c.

◆ rSR

#define rSR   REG(STM32_USART_SR_OFFSET)

Definition at line 81 of file serial.c.

Referenced by dma_reset(), interface_init(), and serial_interrupt().

Function Documentation

◆ dma_reset()

static void dma_reset ( void  )
static

Definition at line 332 of file serial.c.

References dma_packet, rCR3, rDR, rSR, rx_dma, rx_dma_callback(), and tx_dma.

Referenced by interface_init(), rx_dma_callback(), and serial_interrupt().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ interface_init()

void interface_init ( void  )

FMU communications.

Definition at line 90 of file serial.c.

References debug, dma_reset(), PC_COUNT, PC_ELAPSED, perf_alloc, rBRR, rCR1, rCR2, rCR3, rDR, rSR, rx_dma, serial_interrupt(), and tx_dma.

Referenced by user_start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ rx_dma_callback()

static void rx_dma_callback ( DMA_HANDLE  handle,
uint8_t  status,
void *  arg 
)
static

Definition at line 222 of file serial.c.

References IOPacket::crc, crc_packet(), dma_packet, dma_reset(), perf_begin(), perf_end(), PKT_SIZE, rCR3, rDR, rx_handle_packet(), and tx_dma.

Referenced by dma_reset(), and serial_interrupt().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ rx_handle_packet()

static void rx_handle_packet ( void  )
static

Definition at line 156 of file serial.c.

References IOPacket::count_code, IOPacket::crc, crc_packet(), dma_packet, IOPacket::offset, IOPacket::page, perf_count(), PKT_CODE, PKT_CODE_CORRUPT, PKT_CODE_ERROR, PKT_CODE_READ, PKT_CODE_SUCCESS, PKT_CODE_WRITE, PKT_COUNT, PKT_MAX_REGS, registers_get(), registers_set(), and IOPacket::regs.

Referenced by rx_dma_callback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ serial_interrupt()

static int serial_interrupt ( int  irq,
void *  context,
FAR void *  arg 
)
static

Definition at line 258 of file serial.c.

References dma_packet, dma_reset(), perf_count(), PKT_SIZE, rCR1, rDR, rSR, rx_dma, and rx_dma_callback().

Referenced by interface_init().

Here is the call graph for this function:
Here is the caller graph for this function:

Variable Documentation

◆ dma_packet

struct IOPacket dma_packet
static

Definition at line 77 of file serial.c.

Referenced by dma_reset(), rx_dma_callback(), rx_handle_packet(), and serial_interrupt().

◆ pc_badidle

perf_counter_t pc_badidle
static

Definition at line 65 of file serial.c.

◆ pc_crcerr

perf_counter_t pc_crcerr
static

Definition at line 67 of file serial.c.

◆ pc_errors

perf_counter_t pc_errors
static

Definition at line 60 of file serial.c.

◆ pc_fe

perf_counter_t pc_fe
static

Definition at line 62 of file serial.c.

◆ pc_idle

perf_counter_t pc_idle
static

Definition at line 64 of file serial.c.

◆ pc_ne

perf_counter_t pc_ne
static

Definition at line 63 of file serial.c.

◆ pc_ore

perf_counter_t pc_ore
static

Definition at line 61 of file serial.c.

◆ pc_regerr

perf_counter_t pc_regerr
static

Definition at line 66 of file serial.c.

◆ pc_txns

perf_counter_t pc_txns
static

Definition at line 59 of file serial.c.

◆ rx_dma

DMA_HANDLE rx_dma
static

Definition at line 72 of file serial.c.

Referenced by dma_reset(), interface_init(), and serial_interrupt().

◆ tx_dma

DMA_HANDLE tx_dma
static

Definition at line 71 of file serial.c.

Referenced by dma_reset(), interface_init(), and rx_dma_callback().