Serial Port (STM32 / PC)

Serial Port for STM32F4-discovery

The serial port part is hardware dependent. On STM32F4, we have to define the required functions for the autopilot control interface. The Serial port interface requires :

  • Initialization features to start all the required USART, GPIOs, Timers - Method : serial_start()
  • Interrupt service routines to handle Timer and USARTs Interrupts - Method (Hardware) : usart1_isr(),usart3_isr() and tim2_isr().
  • A read function that doesn't block when reading on USART3 (Main USART) - Method : serial_read_message()
  • A write function that takes a MAVLink message and write it to a buffer, then sends the characters of this buffer one at a time - Method : serial_write_message()
  • A Timestamp function that replaces gettimeofday System Call on nix systems.
serial_start ()

This function enables all the required USARTs, GPIOs, and Timers for the correct functionnality of the STM32F4 serial "port".

First we activate the clocks of GPIOD and the 3rd USART :

rcc_periph_clock_enable (RCC_GPIOD);
rcc_periph_clock_enable (RCC_USART3);

and setup all the 4 LEDs :

gpio_mode_setup(GPIOD, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO12 | GPIO13 | GPIO14 | GPIO15);

Then Setup the USART3 with the TX and RX Pins, the required frequency, baudrate and USART3 RX Interrupt (and finally) enable the USART3 :

usart_enable_rx_interrupt (USART3);       
usart_enable (USART3);

We setup the TIM2 timer with a prescaler of 64 and a period of 65535 (for an internal clock frequency of 16 MHz)

timer_set_prescaler(TIM2, 64);
timer_set_period(TIM2, 65535);
usart3_isr ()

While the USART1 Interrupt service routine is not used for the moment, the USART3 ISR is used for the reception of characters in a non blocking manner :

  • Detect if there's a character received on the RX Pin

    void usart3_isr(void){
      static uint8_t data;
    
          if (((USART_CR1(USART3) & USART_CR1_RXNEIE) != 0) 
           && ((USART_SR(USART3) & USART_SR_RXNE) != 0)) {
    
  • If that's the case, start stacking the characters in a buffer.
            if (b_index == N) b_index = 0; 

            data = usart_recv(USART3);

            buffer[b_index] = data;
            b_index++;
        }
    }
  • If the buffer reach full capacity, overwrite it from the beginning :
    if (b_index == N) b_index = 0;
    
  • N = 256 is sufficient for almost all MAVLink messages.
serial_read_message ()

This is the function that's called each time to construct mavlink messages from serial port. USART3_ISR "coordinate" with serial_read_message() in an asymmetric way :

  • serial_read_message()is called multiple time during a single read for any MAVLink message because of the nature of theread_messages()'swhile(!received_all)
  • Because of this feature, each timeserial_read_message() is called, the function that concatenates the characters in MAVLink messages is starting from an arbitrary indexmavlink_index.
  • This index will increment each time the serial_read_message is called, and in the same time, thebuffer(buffer[b_index]) is getting filled with new data.
  • If at any moment the mavlink message is completed, it will get parsed and returned toread_messages() function.
  • If themavlink_index index gets equal to theb_index of the USART3 ISR, or equal to N (max buffer size) it will be reset to 0
msgReceived = mavlink_parse_char (MAVLINK_COMM_1, buffer[mavlink_index], &message, &status);

if (mavlink_index < b_index){
    mavlink_index++;
} else {
    mavlink_index = 0;
}

if(mavlink_index == N) mavlink_index = 0;
serial_write_message ()

This function is called each time we need to send a message to the pixhawk. It first creates a buffer of 300 characters, then copies the MAVLink message to this particular buffer :

volatile char buff[300];
unsigned len = mavlink_msg_to_send_buffer((uint8_t*)buff, &message);

Then it sends the message all at once in a blocking way :

for (int i = 0; i < sizeof(buff); i++) {
                usart_send_blocking(USART3, buff[i]);
        }
get_time_sec()

This function was designed, along with the data structures defined inserial_port.h to replace thegettimeofday() System Call on nix systems which isn't available on Bare metal STM32F4 cortex-m4. It is used for Timestamps and is frequency dependent.

tim2_isr ()

This hardware function has the sole purpose of a hardware clock, to increment ticks at 250 ms each tick. It counts seconds each 4 ticks and is frequency (prescaler and period) dependent. It is responsible for resetting the highres_flag.

Note : This flag is a mean to give a timeout for theread_messages() function ininterface.cppsince we need a timeout mechanism that tells this function to break out of thewhile(!receivedall) loop if there's no Highres message receive.

Admitting that HIGHRES_IMU messages are sent by the pixhawk at a rate of 250 Hz, the max time to wait for such a message is 100 ms, if we didn't receive any message for 250 ms, break out of the loop (This is a condition in the while loop in theread_messages() function)

if (highres_flag == 0) break;

While the highres_flag is defined as 1 each timeread_messages() is called.

Serial Port on nix systems

This follows the same rules as the STM32F4 functions, except it uses theread()/write()system calls and terminos to use the ports allowed by the nix system.

Serial Port header

While defined for STM32F4 (a flag in the corresponding Makefile), the serial_port.h uses the libopencm3 library and includes header file as an exclusive C header file.

It also defines time structures for theget_time_sec()function described earlier

struct timeval {
        time_t      tv_sec;     /* seconds */
        suseconds_t tv_usec;    /* microseconds */
        };
struct timezone {
        int tz_minuteswest;     /* minutes west of Greenwich */
        int tz_dsttime;         /* type of DST correction */
        };

If it's compiled under a nix system, we can define the RS232 device (the serial port device), the baudrate and usart_recv_blocking (which is actually theread() System Call in this case).

The other functionsserial_start(),serial_read_messages(),serial_write_messages(), and get_time_sec() are generaly defined.

results matching ""

    No results matching ""