Classes | Macros | Typedefs | Functions | Variables
uartinterface.c File Reference

This file contains the linux-uart interface functions. More...

#include "toposens/linux/uartinterface.h"
#include <fcntl.h>
#include <pthread.h>
#include <semaphore.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <termios.h>
#include <unistd.h>
#include "toposens/uart_wrapper.h"
Include dependency graph for uartinterface.c:

Go to the source code of this file.

Classes

struct  UartInterface_t
 

Macros

#define UART_LOOP_WAIT_TIME   500
 
#define UART_MAX_PAYLOAD_SIZE   10
 
#define UART_TIMEOUT   1
 Defines how many seconds the ReadUart function will wait for an incoming can-frame. More...
 
#define UART_TIMEOUT_US   0
 Defines how many us the ReadUart function will wait for an incoming can-frame. More...
 

Typedefs

typedef struct UartInterface_t UartInterface_t
 

Functions

int DeinitUARTPort ()
 Called from the can-library, this function will close the socket and take care of ReceiverThread termination. More...
 
static void PrintPayload (uint8_t *Payload_pu8, uint8_t Length_u8)
 Only for debugging - print the content of an UART-Payload to stdout. More...
 
static void PrintUARTPayload (uint8_t *Payload_pu8, uint8_t Length_u8)
 
static ssize_t ReadMsg (uint8_t *Msg_pu8, int InterfaceFS_i)
 Should be called periodically to fetch incoming messages from the socket. More...
 
void * Receiver (void *arg)
 Tries to read CAN frames as long as it is desired. Reacts to abort commands within the set CAN timeout. More...
 
int ReceiverThreadShouldRunUART_b ()
 Reads the while-loop condition in a safe way. More...
 
void RegisterUARTReadCallback (void(*Callback)(uint8_t *UARTMsg_pu8, uint16_t UARTMsgSize_u16, uint8_t InterfaceId_u8))
 This function is called by the library to set a callback function for incoming can-traffic. More...
 
static int SetupInterface (char *InterfaceName_cp, uint32_t InterfaceBitrate_u32)
 Setup of uart-device with given paramters. Currently via system-call. More...
 
int SetupUARTPort (char *InterfaceName_cp, uint32_t InterfaceBitrate_u32, uint8_t InterfaceId_u8)
 Called from the library, this function will take care of all linux-related uart-setup, socket configuration and starting of the receiver thread. More...
 
static void StartReceiverThread (uint8_t InterfaceId_u8, uint32_t InterfaceBitrate_u32, char *InterfaceName_cp)
 Creates the Receiver Thread. More...
 
int WriteUARTPayload (uint8_t *Payload_pu8, uint8_t Length_u8, uint8_t InterfaceId_u8)
 Called to send messages to can socket. More...
 

Variables

static bool ConnectedToUART_b = false
 
static pthread_mutex_t mutex_uart_receiver = PTHREAD_MUTEX_INITIALIZER
 
static void(* ReadCallback )(uint8_t *UARTMsg_pu8, uint16_t DataSize_u16, uint8_t InterfaceId_u8) = NULL
 
static pthread_t receiver_thread_id
 
static bool ReceiverThreadShouldRun = false
 
static sem_t thread_sem
 
static int uart_fs
 
static int UART_fs [MAX_NUMBER_OF_SENSORS_ON_BUS] = {-1}
 

Detailed Description

This file contains the linux-uart interface functions.


Definition in file uartinterface.c.

Macro Definition Documentation

◆ UART_LOOP_WAIT_TIME

#define UART_LOOP_WAIT_TIME   500

Definition at line 35 of file uartinterface.c.

◆ UART_MAX_PAYLOAD_SIZE

#define UART_MAX_PAYLOAD_SIZE   10

Definition at line 34 of file uartinterface.c.

◆ UART_TIMEOUT

#define UART_TIMEOUT   1

Defines how many seconds the ReadUart function will wait for an incoming can-frame.


Definition at line 29 of file uartinterface.c.

◆ UART_TIMEOUT_US

#define UART_TIMEOUT_US   0

Defines how many us the ReadUart function will wait for an incoming can-frame.


Definition at line 33 of file uartinterface.c.

Typedef Documentation

◆ UartInterface_t

Function Documentation

◆ DeinitUARTPort()

int DeinitUARTPort ( )

Called from the can-library, this function will close the socket and take care of ReceiverThread termination.


Returns
int 0 if deinit was successful int 1 in case of an error

Definition at line 204 of file uartinterface.c.

◆ PrintPayload()

static void PrintPayload ( uint8_t *  Payload_pu8,
uint8_t  Length_u8 
)
static

Only for debugging - print the content of an UART-Payload to stdout.


Parameters
[in]Payload_pu8pointer to payload that should be printed
[in]Length_u8length of payload

Definition at line 154 of file uartinterface.c.

◆ PrintUARTPayload()

static void PrintUARTPayload ( uint8_t *  Payload_pu8,
uint8_t  Length_u8 
)
static

Parameters
[in]*Payload_pu8
[in]Length_u8

Definition at line 299 of file uartinterface.c.

◆ ReadMsg()

static ssize_t ReadMsg ( uint8_t *  Msg_pu8,
int  InterfaceFS_i 
)
static

Should be called periodically to fetch incoming messages from the socket.


Parameters
[in]*Msg_pu8
[in]InterfaceFS_i
Returns
can_frame Read-CAN-Frame. If no message was received after timeout, it will retrun an empty frame.

Definition at line 133 of file uartinterface.c.

◆ Receiver()

void * Receiver ( void *  arg)

Tries to read CAN frames as long as it is desired. Reacts to abort commands within the set CAN timeout.


Parameters
[in]*arg

Definition at line 244 of file uartinterface.c.

◆ ReceiverThreadShouldRunUART_b()

int ReceiverThreadShouldRunUART_b ( )

Reads the while-loop condition in a safe way.


Returns
int 0 if receiver should stop int 1 if receiver should be running

Definition at line 233 of file uartinterface.c.

◆ RegisterUARTReadCallback()

void RegisterUARTReadCallback ( void(*)(uint8_t *UARTMsg_pu8, uint16_t UARTMsgSize_u16, uint8_t InterfaceId_u8)  Callback)

This function is called by the library to set a callback function for incoming can-traffic.


Parameters
[in](*Callback)Function Pointer to function that shall be called-back if a can-frame was revived

Definition at line 126 of file uartinterface.c.

◆ SetupInterface()

static int SetupInterface ( char *  InterfaceName_cp,
uint32_t  InterfaceBitrate_u32 
)
static

Setup of uart-device with given paramters. Currently via system-call.


Parameters
[in]*InterfaceName_cpinterface-name that shall be configured
[in]InterfaceBitrate_u32the interface should be working with
Returns
int 0 if setup was successful int 1 in case of an error

Definition at line 163 of file uartinterface.c.

◆ SetupUARTPort()

int SetupUARTPort ( char *  InterfaceName_cp,
uint32_t  InterfaceBitrate_u32,
uint8_t  InterfaceId_u8 
)

Called from the library, this function will take care of all linux-related uart-setup, socket configuration and starting of the receiver thread.


Parameters
[in]*InterfaceName_cpinterface-name that shall be configured
[in]InterfaceBitrate_u32Bitrate the interface should be working with
[in]InterfaceId_u8
Returns
int 0 if setup was successful int 1 in case of an error

Definition at line 189 of file uartinterface.c.

◆ StartReceiverThread()

static void StartReceiverThread ( uint8_t  InterfaceId_u8,
uint32_t  InterfaceBitrate_u32,
char *  InterfaceName_cp 
)
static

Creates the Receiver Thread.


Parameters
[in]InterfaceId_u8
[in]InterfaceBitrate_u32
[in]*InterfaceName_cp

Definition at line 213 of file uartinterface.c.

◆ WriteUARTPayload()

int WriteUARTPayload ( uint8_t *  Payload_pu8,
uint8_t  Length_u8,
uint8_t  InterfaceId_u8 
)

Called to send messages to can socket.


Parameters
[in]*Payload_pu8pointer to payload that should be send
[in]Length_u8
[in]InterfaceId_u8
Returns
int 0 if the writing was successful int 1 in case of an error

Definition at line 140 of file uartinterface.c.

Variable Documentation

◆ ConnectedToUART_b

bool ConnectedToUART_b = false
static

Definition at line 120 of file uartinterface.c.

◆ mutex_uart_receiver

pthread_mutex_t mutex_uart_receiver = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 115 of file uartinterface.c.

◆ ReadCallback

void(* ReadCallback) (uint8_t *UARTMsg_pu8, uint16_t DataSize_u16, uint8_t InterfaceId_u8) = NULL
static

Definition at line 117 of file uartinterface.c.

◆ receiver_thread_id

pthread_t receiver_thread_id
static

Definition at line 109 of file uartinterface.c.

◆ ReceiverThreadShouldRun

bool ReceiverThreadShouldRun = false
static

Definition at line 111 of file uartinterface.c.

◆ thread_sem

sem_t thread_sem
static

Definition at line 113 of file uartinterface.c.

◆ uart_fs

int uart_fs
static

Definition at line 119 of file uartinterface.c.

◆ UART_fs

int UART_fs[MAX_NUMBER_OF_SENSORS_ON_BUS] = {-1}
static

Definition at line 121 of file uartinterface.c.



toposens_echo_driver
Author(s): Tobias Roth , Dennis Maier , Baris Yazici
autogenerated on Mon Feb 28 2022 23:57:42