Skip to content

Commit

Permalink
Merge pull request #289 from paparazzi/stm_uart1_hw_flow_control
Browse files Browse the repository at this point in the history
Add UART hardware flow control (for STM32 only)
  • Loading branch information
flixr committed Oct 5, 2012
2 parents e880b2c + 91ef1c9 commit 816884c
Show file tree
Hide file tree
Showing 10 changed files with 69 additions and 26 deletions.
2 changes: 1 addition & 1 deletion sw/airborne/arch/lpc21/mcu_periph/uart_arch.c
Expand Up @@ -56,7 +56,7 @@ static inline void uart_set_baudrate(struct uart_periph* p, uint32_t baud) {
((uartRegs_t *)(p->reg_addr))->fcr = UART_FIFO_8;
}

void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) {
void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud, bool_t hw_flow_control __attribute__ ((unused))) {
uart_disable_interrupts(p);
uart_set_baudrate(p, baud);
uart_enable_interrupts(p);
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/arch/omap/mcu_periph/uart_arch.c
Expand Up @@ -32,7 +32,7 @@
#include "fms/fms_serial_port.h"


void uart_periph_set_baudrate(struct uart_periph* p, uint16_t baud) {
void uart_periph_set_baudrate(struct uart_periph* p, uint16_t baud, bool_t hw_flow_control __attribute__ ((unused))) {
struct FmsSerialPort* fmssp;
// close serial port if already open
if (p->reg_addr != NULL) {
Expand Down
37 changes: 29 additions & 8 deletions sw/airborne/arch/stm32/mcu_periph/uart_arch.c
Expand Up @@ -30,15 +30,20 @@
#include "std.h"
#include "pprz_baudrate.h"

void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) {
void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud, bool_t hw_flow_control) {

/* Configure USART */
USART_InitTypeDef usart;
usart.USART_BaudRate = baud;
usart.USART_WordLength = USART_WordLength_8b;
usart.USART_StopBits = USART_StopBits_1;
usart.USART_Parity = USART_Parity_No;
usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
if (hw_flow_control) {
usart.USART_HardwareFlowControl = USART_HardwareFlowControl_RTS_CTS;
}
else {
usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
}
usart.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(p->reg_addr, &usart);
/* Enable USART1 Receive interrupts */
Expand Down Expand Up @@ -136,8 +141,25 @@ void uart1_init( void ) {
gpio.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(UART1_RxPort, &gpio);

/* Configure USART1 */
uart_periph_set_baudrate(&uart1, UART1_BAUD);
#if UART1_HW_FLOW_CONTROL
#warning "USING UART1 HW FLOW CONTROL. Make sure to pull down CTS if you are not connecting any flow-control-capable hardware."
/* GPIOA: GPIO_Pin_12 USART1 Rts push-pull */
gpio.GPIO_Pin = UART1_RtsPin;
gpio.GPIO_Mode = GPIO_Mode_AF_PP;
gpio.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(UART1_FlowControlPort, &gpio);

/* GPIOA: GPIO_Pin_11 USART1 Cts pin as floating input */
gpio.GPIO_Pin = UART1_CtsPin;
gpio.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(UART1_FlowControlPort, &gpio);

/* Configure USART1, enable hardware flow control*/
uart_periph_set_baudrate(&uart1, UART1_BAUD, TRUE);
#else
/* Configure USART1, no flow control */
uart_periph_set_baudrate(&uart1, UART1_BAUD, FALSE);
#endif
}

void usart1_irq_handler(void) { usart_irq_handler(&uart1); }
Expand Down Expand Up @@ -171,7 +193,7 @@ void uart2_init( void ) {
GPIO_Init(UART2_RxPort, &gpio);

/* Configure USART2 */
uart_periph_set_baudrate(&uart2, UART2_BAUD);
uart_periph_set_baudrate(&uart2, UART2_BAUD, FALSE);
}

void usart2_irq_handler(void) { usart_irq_handler(&uart2); }
Expand Down Expand Up @@ -207,7 +229,7 @@ void uart3_init( void ) {
GPIO_Init(UART3_RxPort, &gpio);

/* Configure USART3 */
uart_periph_set_baudrate(&uart3, UART3_BAUD);
uart_periph_set_baudrate(&uart3, UART3_BAUD, FALSE);
}

void usart3_irq_handler(void) { usart_irq_handler(&uart3); }
Expand Down Expand Up @@ -242,10 +264,9 @@ void uart5_init( void ) {
GPIO_Init(UART5_RxPort, &gpio);

/* Configure UART5 */
uart_periph_set_baudrate(&uart5, UART5_BAUD);
uart_periph_set_baudrate(&uart5, UART5_BAUD, FALSE);
}

void usart5_irq_handler(void) { usart_irq_handler(&uart5); }

#endif /* USE_UART5 */

8 changes: 8 additions & 0 deletions sw/airborne/arch/stm32/mcu_periph/uart_arch.h
Expand Up @@ -55,6 +55,9 @@
#define UART3_RxPin GPIO_Pin_11
#define UART5_RxPin GPIO_Pin_2

#define UART1_CtsPin GPIO_Pin_11
#define UART1_RtsPin GPIO_Pin_12

#define UART1_TxPort GPIOA
#define UART2_TxPort GPIOA
#define UART3_TxPort GPIOC
Expand All @@ -65,6 +68,8 @@
#define UART3_RxPort GPIOC
#define UART5_RxPort GPIOD

#define UART1_FlowControlPort GPIOA

#define UART1_Periph RCC_APB2Periph_GPIOA
#define UART2_Periph RCC_APB2Periph_GPIOA
#define UART3_Periph RCC_APB2Periph_GPIOC
Expand Down Expand Up @@ -112,6 +117,9 @@
#define UART3_reg USART3
#define UART5_reg USART5

#if defined UART1_FLOW_CONTROL
#error UART1_FLOW_CONTROL is renamed to UART1_HW_FLOW_CONTROL
#endif

#if defined USE_UART1 || OVERRIDE_UART1_IRQ_HANDLER
extern void usart1_irq_handler(void);
Expand Down
16 changes: 10 additions & 6 deletions sw/airborne/mcu_periph/uart.h
Expand Up @@ -57,7 +57,7 @@ struct uart_periph {
};

extern void uart_periph_init(struct uart_periph* p);
extern void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud);
extern void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud, bool_t hw_flow_control);
//extern void uart_periph_init_param(struct uart_periph* p, uint32_t baud, uint8_t mode, uint8_t fmode, char * dev);
extern void uart_transmit(struct uart_periph* p, uint8_t data);
extern bool_t uart_check_free_space(struct uart_periph* p, uint8_t len);
Expand All @@ -82,7 +82,7 @@ extern void uart0_init(void);
#define Uart0ChAvailable() UartChAvailable(uart0)
#define Uart0Getch() UartGetch(uart0)
#define Uart0TxRunning uart0.tx_running
#define Uart0SetBaudrate(_b) uart_periph_set_baudrate(&uart0, _b)
#define Uart0SetBaudrate(_b) uart_periph_set_baudrate(&uart0, _b, 0)
//#define Uart0InitParam(_b, _m, _fm) uart_periph_init_param(&uart0, _b, _m, _fm, "")

#define UART0Init Uart0Init
Expand All @@ -107,7 +107,11 @@ extern void uart1_init(void);
#define Uart1ChAvailable() UartChAvailable(uart1)
#define Uart1Getch() UartGetch(uart1)
#define Uart1TxRunning uart1.tx_running
#define Uart1SetBaudrate(_b) uart_periph_set_baudrate(&uart1, _b)
#if UART1_HW_FLOW_CONTROL
#define Uart1SetBaudrate(_b) uart_periph_set_baudrate(&uart1, _b, TRUE)
#else
#define Uart1SetBaudrate(_b) uart_periph_set_baudrate(&uart1, _b, FALSE)
#endif
//#define Uart1InitParam(_b, _m, _fm) uart_periph_init_param(&uart1, _b, _m, _fm, "")

#define UART1Init Uart1Init
Expand All @@ -132,7 +136,7 @@ extern void uart2_init(void);
#define Uart2ChAvailable() UartChAvailable(uart2)
#define Uart2Getch() UartGetch(uart2)
#define Uart2TxRunning uart2.tx_running
#define Uart2SetBaudrate(_b) uart_periph_set_baudrate(&uart2, _b)
#define Uart2SetBaudrate(_b) uart_periph_set_baudrate(&uart2, _b, FALSE)
//#define Uart2InitParam(_b, _m, _fm) uart_periph_init_param(&uart2, _b, _m, _fm, "")

#define UART2Init Uart2Init
Expand All @@ -157,7 +161,7 @@ extern void uart3_init(void);
#define Uart3ChAvailable() UartChAvailable(uart3)
#define Uart3Getch() UartGetch(uart3)
#define Uart3TxRunning uart3.tx_running
#define Uart3SetBaudrate(_b) uart_periph_set_baudrate(&uart3, _b)
#define Uart3SetBaudrate(_b) uart_periph_set_baudrate(&uart3, _b, FALSE)
//#define Uart3InitParam(_b, _m, _fm) uart_periph_init_param(&uart3, _b, _m, _fm, "")

#define UART3Init Uart3Init
Expand All @@ -182,7 +186,7 @@ extern void uart5_init(void);
#define Uart5ChAvailable() UartChAvailable(uart5)
#define Uart5Getch() UartGetch(uart5)
#define Uart5TxRunning uart5.tx_running
#define Uart5SetBaudrate(_b) uart_periph_set_baudrate(&uart5, _b)
#define Uart5SetBaudrate(_b) uart_periph_set_baudrate(&uart5, _b, FALSE)
//#define Uart5InitParam(_b, _m, _fm) uart_periph_init_param(&uart5, _b, _m, _fm, "")

#define UART5Init Uart5Init
Expand Down
4 changes: 3 additions & 1 deletion sw/ground_segment/tmtc/link.ml
Expand Up @@ -426,6 +426,7 @@ let () =
let ivy_bus = ref Defivybus.default_ivy_bus
and port = ref "/dev/ttyUSB0"
and baudrate = ref "9600"
and hw_flow_control = ref false
and transport = ref "pprz"
and uplink = ref true
and audio = ref false
Expand All @@ -443,6 +444,7 @@ let () =
"-noac_info", Arg.Clear ac_info, (sprintf "Disables AC traffic info (uplink).");
"-nouplink", Arg.Clear uplink, (sprintf "Disables the uplink (from the ground to the aircraft).");
"-s", Arg.Set_string baudrate, (sprintf "<baudrate> Default is %s" !baudrate);
"-hfc", Arg.Set hw_flow_control, "Enable UART hardware flow control (CTS/RTS)";
"-local_timestamp", Arg.Unit (fun () -> add_timestamp := Some (Unix.gettimeofday ())), "Add local timestamp to messages sent over ivy";
"-transport", Arg.Set_string transport, (sprintf "<transport> Available protocols are modem,pprz,pprz2 and xbee. Default is %s" !transport);
"-udp", Arg.Set udp, "Listen a UDP connection on <udp_port>";
Expand Down Expand Up @@ -475,7 +477,7 @@ let () =
end else if !audio then
Demod.init !port
else if on_serial_device then
Serial.opendev !port (Serial.speed_of_baudrate !baudrate)
Serial.opendev !port (Serial.speed_of_baudrate !baudrate) !hw_flow_control
else
Unix.openfile !port [Unix.O_RDWR] 0o640
in
Expand Down
12 changes: 9 additions & 3 deletions sw/lib/ocaml/cserial.c
Expand Up @@ -40,7 +40,7 @@ static int baudrates[] = { B0, B50, B75, B110, B134, B150, B200, B300, B600, B12
/****************************************************************************/
/* Open serial device for requested protocoll */
/****************************************************************************/
value c_init_serial(value device, value speed)
value c_init_serial(value device, value speed, value hw_flow_control)
{
struct termios orig_termios, cur_termios;

Expand All @@ -63,8 +63,14 @@ value c_init_serial(value device, value speed)
cur_termios.c_oflag &=~(OPOST|ONLCR|OCRNL|ONOCR|ONLRET);

/* control modes */
cur_termios.c_cflag &= ~(CSIZE|CSTOPB|CREAD|PARENB|PARODD|HUPCL|CLOCAL|CRTSCTS);
cur_termios.c_cflag |= CREAD|CS8|CLOCAL;
if (Bool_val(hw_flow_control)) {
cur_termios.c_cflag &= ~(CSIZE|CSTOPB|CREAD|PARENB|PARODD|HUPCL|CLOCAL);
cur_termios.c_cflag |= CREAD|CS8|CLOCAL|CRTSCTS;
}
else {
cur_termios.c_cflag &= ~(CSIZE|CSTOPB|CREAD|PARENB|PARODD|HUPCL|CLOCAL|CRTSCTS);
cur_termios.c_cflag |= CREAD|CS8|CLOCAL;
}

/* local modes */
cur_termios.c_lflag &= ~(ISIG|ICANON|IEXTEN|ECHO|FLUSHO|PENDIN);
Expand Down
6 changes: 3 additions & 3 deletions sw/lib/ocaml/serial.ml
Expand Up @@ -77,13 +77,13 @@ let string_of_payload = fun x -> x
let payload_of_string = fun x -> x


external init_serial : string -> speed -> Unix.file_descr = "c_init_serial"
external init_serial : string -> speed -> bool -> Unix.file_descr = "c_init_serial"
external set_dtr : Unix.file_descr -> bool -> unit = "c_set_dtr"
external set_speed : Unix.file_descr -> speed -> unit = "c_serial_set_baudrate"

let opendev device speed =
let opendev device speed hw_flow_control =
try
init_serial device speed
init_serial device speed hw_flow_control
with
Failure x ->
failwith (Printf.sprintf "Error %s (%s)" x device)
Expand Down
2 changes: 1 addition & 1 deletion sw/lib/ocaml/serial.mli
Expand Up @@ -49,7 +49,7 @@ type speed =

val speed_of_baudrate : string -> speed

val opendev : string -> speed -> Unix.file_descr
val opendev : string -> speed -> bool -> Unix.file_descr
val close : Unix.file_descr -> unit
val set_dtr : Unix.file_descr -> bool -> unit
val set_speed : Unix.file_descr -> speed -> unit
Expand Down
6 changes: 4 additions & 2 deletions sw/logalizer/play_core.ml
Expand Up @@ -122,6 +122,7 @@ let was_running = ref false
let bus = ref Defivybus.default_ivy_bus
let port = ref "/dev/ttyUSB0"
let baudrate = ref "9600"
let hw_flow_control = ref false
let file_to_load = ref ""
let output_on_serial = ref false

Expand Down Expand Up @@ -177,7 +178,8 @@ let init = fun () ->
[ "-b", Arg.String (fun x -> bus := x), (sprintf "<ivy bus> Default is %s" !bus);
"-d", Arg.Set_string port, (sprintf "<port> Default is %s" !port);
"-o", Arg.Set output_on_serial, "Output binary messages on serial port";
"-s", Arg.Set_string baudrate, (sprintf "<baudrate> Default is %s" !baudrate)]
"-s", Arg.Set_string baudrate, (sprintf "<baudrate> Default is %s" !baudrate);
"-hfc", Arg.Set hw_flow_control, "Enable UART hardware flow control (CTS/RTS)";]
(fun x -> file_to_load := x)
"Usage: ";

Expand All @@ -187,7 +189,7 @@ let init = fun () ->

let serial_port =
if !output_on_serial then
Some (Unix.out_channel_of_descr (Serial.opendev !port (Serial.speed_of_baudrate !baudrate)))
Some (Unix.out_channel_of_descr (Serial.opendev !port (Serial.speed_of_baudrate !baudrate) !hw_flow_control))
else
None in

Expand Down

0 comments on commit 816884c

Please sign in to comment.