uartinterface.c
Go to the documentation of this file.
1 
8 /*---- "module header" ----------------------------------------------------------------*/
10 /*---- <system includes> --------------------------------------------------------------*/
11 #include <fcntl.h> //Used for UART
12 #include <pthread.h>
13 #include <semaphore.h>
14 #include <stdbool.h>
15 #include <stdio.h>
16 #include <stdlib.h>
17 #include <string.h>
18 #include <termios.h> //Used for UART
19 #include <unistd.h>
20 
21 /*---- "library includes" -------------------------------------------------------------*/
22 #include "toposens/uart_wrapper.h"
23 /*---- "project includes" -------------------------------------------------------------*/
24 
25 /*---- local macros and constants -----------------------------------------------------*/
29 #define UART_TIMEOUT 1
30 
33 #define UART_TIMEOUT_US 0
34 #define UART_MAX_PAYLOAD_SIZE 10
35 #define UART_LOOP_WAIT_TIME 500
36 /*---- local types --------------------------------------------------------------------*/
37 typedef struct UartInterface_t
38 {
39  uint8_t InterfaceId_u8;
43 /*---- local functions prototypes -----------------------------------------------------*/
44 
53 static int SetupInterface(char* InterfaceName_cp, uint32_t InterfaceBitrate_u32);
54 
62 static void StartReceiverThread(uint8_t InterfaceId_u8, uint32_t InterfaceBitrate_u32,
63  char* InterfaceName_cp);
64 
72 
79 void* Receiver(void* arg);
80 
89 static ssize_t ReadMsg(uint8_t* Msg_pu8, int InterfaceFS_i);
90 
96 static void PrintUARTPayload(uint8_t* Payload_pu8, uint8_t Length_u8);
97 
104 static void PrintPayload(uint8_t* Payload_pu8, uint8_t Length_u8);
105 /*---- local inline functions ---------------------------------------------------------*/
106 
107 /*---- local variables (static) -------------------------------------------------------*/
108 // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
109 static pthread_t receiver_thread_id;
110 // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
111 static bool ReceiverThreadShouldRun = false;
112 // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
113 static sem_t thread_sem;
114 // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
115 static pthread_mutex_t mutex_uart_receiver = PTHREAD_MUTEX_INITIALIZER;
116 // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
117 static void (*ReadCallback)(uint8_t* UARTMsg_pu8, uint16_t DataSize_u16,
118  uint8_t InterfaceId_u8) = NULL;
119 static int uart_fs;
120 static bool ConnectedToUART_b = false;
122 /*---- public variables ---------------------------------------------------------------*/
123 
124 /*---- functions ----------------------------------------------------------------------*/
125 
126 void RegisterUARTReadCallback(void (*Callback)(uint8_t* UARTMsg_pu8, uint16_t UARTMsgSize_u16,
127  uint8_t InterfaceId_u8))
128 {
129  MPRINTF("RegisterReadCallback\n");
130  ReadCallback = Callback;
131 }
132 
133 static ssize_t ReadMsg(uint8_t* Msg_pu8, int InterfaceFS_i)
134 {
135  ssize_t Length = 0;
136  Length = read(InterfaceFS_i, Msg_pu8, UART_MAX_BUF_LEN);
137  return Length;
138 }
139 
140 int WriteUARTPayload(uint8_t* Payload_pu8, uint8_t Length_u8, uint8_t InterfaceId_u8)
141 {
142  PrintUARTPayload(Payload_pu8, Length_u8);
143  int16_t BytesWritten_i16 = 0;
144  BytesWritten_i16 = write(UART_fs[InterfaceId_u8], Payload_pu8, Length_u8);
145  if (BytesWritten_i16 < 0)
146  {
147  perror("Write");
148  return 1;
149  }
150  MPRINTF("Wrote %d Bytes\n", BytesWritten_i16);
151  return 0;
152 }
153 
154 static void PrintPayload(uint8_t* Payload_pu8, uint8_t Length_u8)
155 {
156  for (int i = 0; i < Length_u8; i++)
157  {
158  MPRINTF("%02X ", Payload_pu8[i]);
159  }
160  MPRINTF("\r\n");
161 }
162 
163 static int SetupInterface(char* InterfaceName_cp, uint32_t InterfaceBitrate_u32)
164 {
165  MPRINTF("SetupInterface\n");
166 
167  uart_fs = -1;
168  uart_fs = open(InterfaceName_cp, O_RDWR | O_NOCTTY | O_CLOEXEC);
169 
170  if (uart_fs == -1)
171  {
172  MPRINTF("Error - Unable to open UART. Ensure it is not in use by another application\n");
173  }
174  else
175  {
176  struct termios options;
177  memset(&options, 0x00, sizeof(options));
178  tcgetattr(uart_fs, &options);
179  options.c_cflag = InterfaceBitrate_u32 | CS8 | CLOCAL | CREAD; //<Set baud rate
180  options.c_iflag = IGNPAR;
181  options.c_oflag = 0;
182  options.c_lflag = 0;
183  tcflush(uart_fs, TCIFLUSH);
184  tcsetattr(uart_fs, TCSANOW, &options);
185  }
186  return uart_fs;
187 }
188 
189 int SetupUARTPort(char* InterfaceName_cp, uint32_t InterfaceBitrate_u32, uint8_t InterfaceId_u8)
190 {
191  sem_init(&thread_sem, 0, 1);
192  pthread_mutex_lock(&mutex_uart_receiver);
194  pthread_mutex_unlock(&mutex_uart_receiver);
195  sem_wait(&thread_sem);
196  StartReceiverThread(InterfaceId_u8, InterfaceBitrate_u32, InterfaceName_cp);
197  sem_wait(&thread_sem);
198  sem_post(&thread_sem);
199 
200  ConnectedToUART_b = true;
201  return 0;
202 }
203 
205 {
206  pthread_mutex_lock(&mutex_uart_receiver);
207  ReceiverThreadShouldRun = false;
208  pthread_mutex_unlock(&mutex_uart_receiver);
209  (void)pthread_join(receiver_thread_id, NULL);
210  return 0;
211 }
212 
213 static void StartReceiverThread(uint8_t InterfaceId_u8, uint32_t InterfaceBitrate_u32,
214  char* InterfaceName_cp)
215 {
216  MPRINTF("StartReceiverThread\n");
217  UartInterface_t* NewInterface_pt = malloc(sizeof(*NewInterface_pt));
218  memcpy(NewInterface_pt->InterfaceName, InterfaceName_cp, DEVICE_NAME_LEN);
219  NewInterface_pt->InterfaceId_u8 = InterfaceId_u8;
220  NewInterface_pt->InterfaceBitrate_u32 = InterfaceBitrate_u32;
221  int err = 0;
222  err = pthread_create(&(receiver_thread_id), NULL, &Receiver, NewInterface_pt);
223  if (err != 0)
224  {
225  MPRINTF("\ncan't create thread :[%s]", strerror(err));
226  }
227  else
228  {
229  MPRINTF("UART-Receiver Thread created successfully\n");
230  }
231 }
232 
234 {
235  int value = 0;
236 
237  pthread_mutex_lock(&mutex_uart_receiver);
238  value = ReceiverThreadShouldRun;
239  pthread_mutex_unlock(&mutex_uart_receiver);
240 
241  return value;
242 }
243 
244 void* Receiver(void* arg)
245 {
246  UartInterface_t* NewInterface_pt = (UartInterface_t*)arg;
247  UartInterface_t NewInterface;
248  memcpy(&NewInterface, NewInterface_pt, sizeof(NewInterface));
249  free(arg);
250  uint32_t Bitrate_u32 = NewInterface.InterfaceBitrate_u32;
251 #ifndef NOREALPRINTF
252  uint8_t InterfaceId_u8 = NewInterface.InterfaceId_u8;
253 #endif
254  char* InterfaceName = NewInterface.InterfaceName;
255  MPRINTF("--------------------\n");
256  MPRINTF("Add New Interface: \n");
257  MPRINTF("Bitrate: %d\n", Bitrate_u32);
258 #ifndef NOREALPRINTF
259  MPRINTF("InterfaceId_u8: %d\n", InterfaceId_u8);
260 #endif
261  MPRINTF("InterfaceName: %s\n", InterfaceName);
262  int InterfaceFS_i = SetupInterface(InterfaceName, Bitrate_u32);
263  MPRINTF("InterfaceFS_i: %d\n", InterfaceFS_i);
264  MPRINTF("--------------------\n");
265  UART_fs[NewInterface.InterfaceId_u8] = InterfaceFS_i;
266  if (InterfaceFS_i > 0)
267  {
268  MPRINTF("Interface setup successful\n");
269  }
270  else
271  {
272  MPRINTF("Interface setup failed\n");
273  }
274  sem_post(&thread_sem);
275  uint8_t Payload_pu8[UART_MAX_BUF_LEN] = {0};
277  {
278  ssize_t Size = ReadMsg(Payload_pu8, InterfaceFS_i);
279  MPRINTF("Test Size: %zd\n", Size);
280  if (Size > 0)
281  {
282  PrintUARTPayload(Payload_pu8, Size);
283  if (ReadCallback != NULL)
284  {
285  if (Size < UINT8_MAX)
286  {
287  uint8_t Size_u8 = (uint8_t)Size;
288  ReadCallback(Payload_pu8, Size_u8, NewInterface.InterfaceId_u8);
289  }
290  }
291  }
292  usleep(UART_LOOP_WAIT_TIME);
293  }
294  close(InterfaceFS_i);
295  MPRINTF("End Receiver\n");
296  return NULL;
297 }
298 
299 static void PrintUARTPayload(uint8_t* Payload_pu8, uint8_t Length_u8)
300 {
301  MPRINTF("Payload: \n ");
302  for (uint8_t Idx_u8 = 0; Idx_u8 < Length_u8; Idx_u8++)
303  {
304  MPRINTF("%02X ", Payload_pu8[Idx_u8]);
305  }
306  MPRINTF("\n");
307 }
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,...
Definition: uartinterface.c:189
PrintUARTPayload
static void PrintUARTPayload(uint8_t *Payload_pu8, uint8_t Length_u8)
Definition: uartinterface.c:299
MAX_NUMBER_OF_SENSORS_ON_BUS
#define MAX_NUMBER_OF_SENSORS_ON_BUS
If this define is set, the library will use the linux socket interface.
Definition: sensor_lib_config.h:35
thread_sem
static sem_t thread_sem
Definition: uartinterface.c:113
receiver_thread_id
static pthread_t receiver_thread_id
Definition: uartinterface.c:109
UartInterface_t::InterfaceBitrate_u32
uint32_t InterfaceBitrate_u32
Definition: uartinterface.c:41
RegisterUARTReadCallback
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.
Definition: uartinterface.c:126
StartReceiverThread
static void StartReceiverThread(uint8_t InterfaceId_u8, uint32_t InterfaceBitrate_u32, char *InterfaceName_cp)
Creates the Receiver Thread.
Definition: uartinterface.c:213
UartInterface_t
struct UartInterface_t UartInterface_t
mutex_uart_receiver
static pthread_mutex_t mutex_uart_receiver
Definition: uartinterface.c:115
UART_MAX_BUF_LEN
#define UART_MAX_BUF_LEN
Definition: uart_wrapper.h:20
UartInterface_t::InterfaceId_u8
uint8_t InterfaceId_u8
Definition: uartinterface.c:39
ReadCallback
static void(* ReadCallback)(uint8_t *UARTMsg_pu8, uint16_t DataSize_u16, uint8_t InterfaceId_u8)
Definition: uartinterface.c:117
UartInterface_t
Definition: uartinterface.c:37
uart_fs
static int uart_fs
Definition: uartinterface.c:119
uart_wrapper.h
Header for UART wrapper.
ConnectedToUART_b
static bool ConnectedToUART_b
Definition: uartinterface.c:120
DeinitUARTPort
int DeinitUARTPort()
Called from the can-library, this function will close the socket and take care of ReceiverThread term...
Definition: uartinterface.c:204
SetupInterface
static int SetupInterface(char *InterfaceName_cp, uint32_t InterfaceBitrate_u32)
Setup of uart-device with given paramters. Currently via system-call.
Definition: uartinterface.c:163
MPRINTF
#define MPRINTF(f_,...)
Definition: sensor_lib_config.h:53
uartinterface.h
This file contains the linux-uart interface prototypes.
ReceiverThreadShouldRunUART_b
int ReceiverThreadShouldRunUART_b()
Reads the while-loop condition in a safe way.
Definition: uartinterface.c:233
ReadMsg
static ssize_t ReadMsg(uint8_t *Msg_pu8, int InterfaceFS_i)
Should be called periodically to fetch incoming messages from the socket.
Definition: uartinterface.c:133
Length
Length
Receiver
void * Receiver(void *arg)
Tries to read CAN frames as long as it is desired. Reacts to abort commands within the set CAN timeou...
Definition: uartinterface.c:244
DEVICE_NAME_LEN
#define DEVICE_NAME_LEN
Definition: sensor_lib_config.h:59
UartInterface_t::InterfaceName
char InterfaceName[DEVICE_NAME_LEN]
Definition: uartinterface.c:40
PrintPayload
static void PrintPayload(uint8_t *Payload_pu8, uint8_t Length_u8)
Only for debugging - print the content of an UART-Payload to stdout.
Definition: uartinterface.c:154
UART_LOOP_WAIT_TIME
#define UART_LOOP_WAIT_TIME
Definition: uartinterface.c:35
ReceiverThreadShouldRun
static bool ReceiverThreadShouldRun
Definition: uartinterface.c:111
WriteUARTPayload
int WriteUARTPayload(uint8_t *Payload_pu8, uint8_t Length_u8, uint8_t InterfaceId_u8)
Called to send messages to can socket.
Definition: uartinterface.c:140
UART_fs
static int UART_fs[MAX_NUMBER_OF_SENSORS_ON_BUS]
Definition: uartinterface.c:121


toposens_echo_driver
Author(s): Tobias Roth , Dennis Maier , Baris Yazici
autogenerated on Wed Mar 2 2022 01:12:32