13 #include <semaphore.h> 29 #define UART_TIMEOUT 1 33 #define UART_TIMEOUT_US 0 34 #define UART_MAX_PAYLOAD_SIZE 10 35 #define UART_LOOP_WAIT_TIME 500 63 char* InterfaceName_cp);
89 static ssize_t
ReadMsg(uint8_t* Msg_pu8,
int InterfaceFS_i);
104 static void PrintPayload(uint8_t* Payload_pu8, uint8_t Length_u8);
117 static void (*
ReadCallback)(uint8_t* UARTMsg_pu8, uint16_t DataSize_u16,
129 MPRINTF(
"RegisterReadCallback\n");
133 static ssize_t
ReadMsg(uint8_t* Msg_pu8,
int InterfaceFS_i)
143 int16_t BytesWritten_i16 = 0;
144 BytesWritten_i16 = write(
UART_fs[InterfaceId_u8], Payload_pu8, Length_u8);
145 if (BytesWritten_i16 < 0)
150 MPRINTF(
"Wrote %d Bytes\n", BytesWritten_i16);
156 for (
int i = 0; i < Length_u8; i++)
158 MPRINTF(
"%02X ", Payload_pu8[i]);
168 uart_fs = open(InterfaceName_cp, O_RDWR | O_NOCTTY | O_CLOEXEC);
172 MPRINTF(
"Error - Unable to open UART. Ensure it is not in use by another application\n");
176 struct termios options;
177 memset(&options, 0x00,
sizeof(options));
179 options.c_cflag = InterfaceBitrate_u32 | CS8 | CLOCAL | CREAD;
180 options.c_iflag = IGNPAR;
184 tcsetattr(
uart_fs, TCSANOW, &options);
214 char* InterfaceName_cp)
216 MPRINTF(
"StartReceiverThread\n");
225 MPRINTF(
"\ncan't create thread :[%s]", strerror(err));
229 MPRINTF(
"UART-Receiver Thread created successfully\n");
248 memcpy(&NewInterface, NewInterface_pt,
sizeof(NewInterface));
255 MPRINTF(
"--------------------\n");
256 MPRINTF(
"Add New Interface: \n");
257 MPRINTF(
"Bitrate: %d\n", Bitrate_u32);
259 MPRINTF(
"InterfaceId_u8: %d\n", InterfaceId_u8);
261 MPRINTF(
"InterfaceName: %s\n", InterfaceName);
263 MPRINTF(
"InterfaceFS_i: %d\n", InterfaceFS_i);
264 MPRINTF(
"--------------------\n");
266 if (InterfaceFS_i > 0)
268 MPRINTF(
"Interface setup successful\n");
272 MPRINTF(
"Interface setup failed\n");
278 ssize_t Size =
ReadMsg(Payload_pu8, InterfaceFS_i);
279 MPRINTF(
"Test Size: %zd\n", Size);
285 if (Size < UINT8_MAX)
287 uint8_t Size_u8 = (uint8_t)Size;
294 close(InterfaceFS_i);
302 for (uint8_t Idx_u8 = 0; Idx_u8 < Length_u8; Idx_u8++)
304 MPRINTF(
"%02X ", Payload_pu8[Idx_u8]);
#define MAX_NUMBER_OF_SENSORS_ON_BUS
If this define is set, the library will use the linux socket interface.
int DeinitUARTPort()
Called from the can-library, this function will close the socket and take care of ReceiverThread term...
struct UartInterface_t UartInterface_t
static bool ReceiverThreadShouldRun
static int UART_fs[MAX_NUMBER_OF_SENSORS_ON_BUS]
int WriteUARTPayload(uint8_t *Payload_pu8, uint8_t Length_u8, uint8_t InterfaceId_u8)
Called to send messages to can socket.
uint32_t InterfaceBitrate_u32
static int SetupInterface(char *InterfaceName_cp, uint32_t InterfaceBitrate_u32)
Setup of uart-device with given paramters. Currently via system-call.
static void PrintUARTPayload(uint8_t *Payload_pu8, uint8_t Length_u8)
static pthread_mutex_t mutex_uart_receiver
static void PrintPayload(uint8_t *Payload_pu8, uint8_t Length_u8)
Only for debugging - print the content of an UART-Payload to stdout.
static void StartReceiverThread(uint8_t InterfaceId_u8, uint32_t InterfaceBitrate_u32, char *InterfaceName_cp)
Creates the Receiver Thread.
int ReceiverThreadShouldRunUART_b()
Reads the while-loop condition in a safe way.
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.
static ssize_t ReadMsg(uint8_t *Msg_pu8, int InterfaceFS_i)
Should be called periodically to fetch incoming messages from the socket.
static bool ConnectedToUART_b
#define UART_LOOP_WAIT_TIME
static void(* ReadCallback)(uint8_t *UARTMsg_pu8, uint16_t DataSize_u16, uint8_t InterfaceId_u8)
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.
This file contains the linux-uart interface prototypes.
void * Receiver(void *arg)
Tries to read CAN frames as long as it is desired. Reacts to abort commands within the set CAN timeou...
static pthread_t receiver_thread_id
char InterfaceName[DEVICE_NAME_LEN]