moved some files
This commit is contained in:
1
thirdparty/libcsp/src/drivers/CMakeLists.txt
vendored
Normal file
1
thirdparty/libcsp/src/drivers/CMakeLists.txt
vendored
Normal file
@ -0,0 +1 @@
|
||||
add_subdirectory(can)
|
3
thirdparty/libcsp/src/drivers/can/CMakeLists.txt
vendored
Normal file
3
thirdparty/libcsp/src/drivers/can/CMakeLists.txt
vendored
Normal file
@ -0,0 +1,3 @@
|
||||
target_sources(${LIB_CSP_NAME} PRIVATE
|
||||
can_socketcan.c
|
||||
)
|
201
thirdparty/libcsp/src/drivers/can/can_socketcan.c
vendored
Normal file
201
thirdparty/libcsp/src/drivers/can/can_socketcan.c
vendored
Normal file
@ -0,0 +1,201 @@
|
||||
/*
|
||||
Cubesat Space Protocol - A small network-layer protocol designed for Cubesats
|
||||
Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com)
|
||||
Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk)
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
/* SocketCAN driver */
|
||||
#include <csp/drivers/can_socketcan.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
#include <time.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <pthread.h>
|
||||
#include <semaphore.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/socket.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <net/if.h>
|
||||
#include <sys/queue.h>
|
||||
#include <sys/uio.h>
|
||||
#include <sys/time.h>
|
||||
#include <net/if.h>
|
||||
|
||||
#include <linux/can.h>
|
||||
#include <linux/can/raw.h>
|
||||
#include <linux/socket.h>
|
||||
|
||||
#include <csp/csp.h>
|
||||
#include <csp/interfaces/csp_if_can.h>
|
||||
|
||||
#ifdef CSP_HAVE_LIBSOCKETCAN
|
||||
#include <libsocketcan.h>
|
||||
#endif
|
||||
|
||||
static struct can_socketcan_s {
|
||||
int socket;
|
||||
csp_iface_t interface;
|
||||
} socketcan[1] = {
|
||||
{
|
||||
.interface = {
|
||||
.name = "CAN",
|
||||
.nexthop = csp_can_tx,
|
||||
.mtu = CSP_CAN_MTU,
|
||||
.driver = &socketcan[0],
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static void * socketcan_rx_thread(void * parameters)
|
||||
{
|
||||
struct can_frame frame;
|
||||
int nbytes;
|
||||
|
||||
while (1) {
|
||||
/* Read CAN frame */
|
||||
nbytes = read(socketcan[0].socket, &frame, sizeof(frame));
|
||||
if (nbytes < 0) {
|
||||
csp_log_error("read: %s", strerror(errno));
|
||||
continue;
|
||||
}
|
||||
|
||||
if (nbytes != sizeof(frame)) {
|
||||
csp_log_warn("Read incomplete CAN frame");
|
||||
continue;
|
||||
}
|
||||
|
||||
/* Frame type */
|
||||
if (frame.can_id & (CAN_ERR_FLAG | CAN_RTR_FLAG) || !(frame.can_id & CAN_EFF_FLAG)) {
|
||||
/* Drop error and remote frames */
|
||||
csp_log_warn("Discarding ERR/RTR/SFF frame");
|
||||
continue;
|
||||
}
|
||||
|
||||
/* Strip flags */
|
||||
frame.can_id &= CAN_EFF_MASK;
|
||||
|
||||
/* Call RX callbacsp_can_rx_frameck */
|
||||
csp_can_rx(&socketcan[0].interface, frame.can_id, frame.data, frame.can_dlc, NULL);
|
||||
}
|
||||
|
||||
/* We should never reach this point */
|
||||
pthread_exit(NULL);
|
||||
}
|
||||
|
||||
|
||||
int csp_can_tx_frame(csp_iface_t *interface, uint32_t id, const uint8_t * data, uint8_t dlc)
|
||||
{
|
||||
struct can_frame frame;
|
||||
int i, tries = 0;
|
||||
memset(&frame, 0, sizeof(frame));
|
||||
if (dlc > 8)
|
||||
return -1;
|
||||
|
||||
/* Copy identifier */
|
||||
frame.can_id = id | CAN_EFF_FLAG;
|
||||
|
||||
/* Copy data to frame */
|
||||
for (i = 0; i < dlc; i++)
|
||||
frame.data[i] = data[i];
|
||||
|
||||
/* Set DLC */
|
||||
frame.can_dlc = dlc;
|
||||
|
||||
/* Send frame */
|
||||
while (write(socketcan[0].socket, &frame, sizeof(frame)) != sizeof(frame)) {
|
||||
if (++tries < 1000 && errno == ENOBUFS) {
|
||||
/* Wait 10 ms and try again */
|
||||
usleep(10000);
|
||||
} else {
|
||||
csp_log_error("write: %s", strerror(errno));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
csp_iface_t * csp_can_socketcan_init(const char * ifc, int bitrate, int promisc)
|
||||
{
|
||||
struct ifreq ifr;
|
||||
struct sockaddr_can addr;
|
||||
pthread_t rx_thread;
|
||||
|
||||
printf("-I-: Initiating CAN interface %s\n", ifc);
|
||||
|
||||
#ifdef CSP_HAVE_LIBSOCKETCAN
|
||||
/* Set interface up */
|
||||
if (bitrate > 0) {
|
||||
can_do_stop(ifc);
|
||||
can_set_bitrate(ifc, bitrate);
|
||||
can_set_restart_ms(ifc, 100);
|
||||
can_do_start(ifc);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Create socket */
|
||||
if ((socketcan[0].socket = socket(PF_CAN, SOCK_RAW, CAN_RAW)) < 0) {
|
||||
csp_log_error("socket: %s", strerror(errno));
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/* Locate interface */
|
||||
strncpy(ifr.ifr_name, ifc, IFNAMSIZ - 1);
|
||||
if (ioctl(socketcan[0].socket, SIOCGIFINDEX, &ifr) < 0) {
|
||||
csp_log_error("ioctl: %s", strerror(errno));
|
||||
return NULL;
|
||||
}
|
||||
memset(&addr, 0, sizeof(addr));
|
||||
/* Bind the socket to CAN interface */
|
||||
addr.can_family = AF_CAN;
|
||||
addr.can_ifindex = ifr.ifr_ifindex;
|
||||
if (bind(socketcan[0].socket, (struct sockaddr *)&addr, sizeof(addr)) < 0) {
|
||||
csp_log_error("bind: %s", strerror(errno));
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/* Set filter mode */
|
||||
if (promisc == 0) {
|
||||
|
||||
struct can_filter filter;
|
||||
filter.can_id = CFP_MAKE_DST(csp_get_address());
|
||||
filter.can_mask = CFP_MAKE_DST((1 << CFP_HOST_SIZE) - 1);
|
||||
|
||||
if (setsockopt(socketcan[0].socket, SOL_CAN_RAW, CAN_RAW_FILTER, &filter, sizeof(filter)) < 0) {
|
||||
csp_log_error("setsockopt: %s", strerror(errno));
|
||||
return NULL;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/* Create receive thread */
|
||||
if (pthread_create(&rx_thread, NULL, socketcan_rx_thread, NULL) != 0) {
|
||||
csp_log_error("pthread_create: %s", strerror(errno));
|
||||
return NULL;
|
||||
}
|
||||
|
||||
csp_iflist_add(&socketcan[0].interface);
|
||||
|
||||
return &socketcan[0].interface;
|
||||
}
|
254
thirdparty/libcsp/src/drivers/usart/usart_linux.c
vendored
Normal file
254
thirdparty/libcsp/src/drivers/usart/usart_linux.c
vendored
Normal file
@ -0,0 +1,254 @@
|
||||
/*
|
||||
Cubesat Space Protocol - A small network-layer protocol designed for Cubesats
|
||||
Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com)
|
||||
Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk)
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
#include <csp/drivers/usart.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <time.h>
|
||||
#include <pthread.h>
|
||||
#include <unistd.h>
|
||||
#include <errno.h>
|
||||
#include <termios.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <csp/csp.h>
|
||||
#include <sys/time.h>
|
||||
|
||||
int fd;
|
||||
usart_callback_t usart_callback = NULL;
|
||||
|
||||
static void *serial_rx_thread(void *vptr_args);
|
||||
|
||||
int getbaud(int ifd) {
|
||||
struct termios termAttr;
|
||||
int inputSpeed = -1;
|
||||
speed_t baudRate;
|
||||
tcgetattr(ifd, &termAttr);
|
||||
/* Get the input speed. */
|
||||
baudRate = cfgetispeed(&termAttr);
|
||||
switch (baudRate) {
|
||||
case B0:
|
||||
inputSpeed = 0;
|
||||
break;
|
||||
case B50:
|
||||
inputSpeed = 50;
|
||||
break;
|
||||
case B110:
|
||||
inputSpeed = 110;
|
||||
break;
|
||||
case B134:
|
||||
inputSpeed = 134;
|
||||
break;
|
||||
case B150:
|
||||
inputSpeed = 150;
|
||||
break;
|
||||
case B200:
|
||||
inputSpeed = 200;
|
||||
break;
|
||||
case B300:
|
||||
inputSpeed = 300;
|
||||
break;
|
||||
case B600:
|
||||
inputSpeed = 600;
|
||||
break;
|
||||
case B1200:
|
||||
inputSpeed = 1200;
|
||||
break;
|
||||
case B1800:
|
||||
inputSpeed = 1800;
|
||||
break;
|
||||
case B2400:
|
||||
inputSpeed = 2400;
|
||||
break;
|
||||
case B4800:
|
||||
inputSpeed = 4800;
|
||||
break;
|
||||
case B9600:
|
||||
inputSpeed = 9600;
|
||||
break;
|
||||
case B19200:
|
||||
inputSpeed = 19200;
|
||||
break;
|
||||
case B38400:
|
||||
inputSpeed = 38400;
|
||||
break;
|
||||
case B57600:
|
||||
inputSpeed = 57600;
|
||||
break;
|
||||
case B115200:
|
||||
inputSpeed = 115200;
|
||||
break;
|
||||
case B230400:
|
||||
inputSpeed = 230400;
|
||||
break;
|
||||
#ifndef CSP_MACOSX
|
||||
case B460800:
|
||||
inputSpeed = 460800;
|
||||
break;
|
||||
case B500000:
|
||||
inputSpeed = 500000;
|
||||
break;
|
||||
case B576000:
|
||||
inputSpeed = 576000;
|
||||
break;
|
||||
case B921600:
|
||||
inputSpeed = 921600;
|
||||
break;
|
||||
case B1000000:
|
||||
inputSpeed = 1000000;
|
||||
break;
|
||||
case B1152000:
|
||||
inputSpeed = 1152000;
|
||||
break;
|
||||
case B1500000:
|
||||
inputSpeed = 1500000;
|
||||
break;
|
||||
case B2000000:
|
||||
inputSpeed = 2000000;
|
||||
break;
|
||||
case B2500000:
|
||||
inputSpeed = 2500000;
|
||||
break;
|
||||
case B3000000:
|
||||
inputSpeed = 3000000;
|
||||
break;
|
||||
case B3500000:
|
||||
inputSpeed = 3500000;
|
||||
break;
|
||||
case B4000000:
|
||||
inputSpeed = 4000000;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
return inputSpeed;
|
||||
|
||||
}
|
||||
|
||||
void usart_init(struct usart_conf * conf) {
|
||||
|
||||
struct termios options;
|
||||
pthread_t rx_thread;
|
||||
|
||||
fd = open(conf->device, O_RDWR | O_NOCTTY | O_NONBLOCK);
|
||||
|
||||
if (fd < 0) {
|
||||
printf("Failed to open %s: %s\r\n", conf->device, strerror(errno));
|
||||
return;
|
||||
}
|
||||
|
||||
int brate = 0;
|
||||
switch(conf->baudrate) {
|
||||
case 4800: brate=B4800; break;
|
||||
case 9600: brate=B9600; break;
|
||||
case 19200: brate=B19200; break;
|
||||
case 38400: brate=B38400; break;
|
||||
case 57600: brate=B57600; break;
|
||||
case 115200: brate=B115200; break;
|
||||
case 230400: brate=B230400; break;
|
||||
#ifndef CSP_MACOSX
|
||||
case 460800: brate=B460800; break;
|
||||
case 500000: brate=B500000; break;
|
||||
case 576000: brate=B576000; break;
|
||||
case 921600: brate=B921600; break;
|
||||
case 1000000: brate=B1000000; break;
|
||||
case 1152000: brate=B1152000; break;
|
||||
case 1500000: brate=B1500000; break;
|
||||
case 2000000: brate=B2000000; break;
|
||||
case 2500000: brate=B2500000; break;
|
||||
case 3000000: brate=B3000000; break;
|
||||
case 3500000: brate=B3500000; break;
|
||||
case 4000000: brate=B4000000; break;
|
||||
#endif
|
||||
default:
|
||||
printf("Unsupported baudrate requested, defaulting to 500000, requested baudrate=%u\n", conf->baudrate);
|
||||
brate=B500000;
|
||||
break;
|
||||
}
|
||||
|
||||
tcgetattr(fd, &options);
|
||||
cfsetispeed(&options, brate);
|
||||
cfsetospeed(&options, brate);
|
||||
options.c_cflag |= (CLOCAL | CREAD);
|
||||
options.c_cflag &= ~PARENB;
|
||||
options.c_cflag &= ~CSTOPB;
|
||||
options.c_cflag &= ~CSIZE;
|
||||
options.c_cflag |= CS8;
|
||||
options.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
|
||||
options.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | INLCR | PARMRK | INPCK | ISTRIP | IXON);
|
||||
options.c_oflag &= ~(OCRNL | ONLCR | ONLRET | ONOCR | OFILL | OPOST);
|
||||
options.c_cc[VTIME] = 0;
|
||||
options.c_cc[VMIN] = 1;
|
||||
tcsetattr(fd, TCSANOW, &options);
|
||||
if (tcgetattr(fd, &options) == -1)
|
||||
perror("error setting options");
|
||||
fcntl(fd, F_SETFL, 0);
|
||||
|
||||
/* Flush old transmissions */
|
||||
if (tcflush(fd, TCIOFLUSH) == -1)
|
||||
printf("Error flushing serial port - %s(%d).\n", strerror(errno), errno);
|
||||
|
||||
if (pthread_create(&rx_thread, NULL, serial_rx_thread, NULL) != 0)
|
||||
return;
|
||||
|
||||
}
|
||||
|
||||
void usart_set_callback(usart_callback_t callback) {
|
||||
usart_callback = callback;
|
||||
}
|
||||
|
||||
void usart_insert(char c, void * pxTaskWoken) {
|
||||
printf("%c", c);
|
||||
}
|
||||
|
||||
void usart_putstr(char * buf, int len) {
|
||||
if (write(fd, buf, len) != len)
|
||||
return;
|
||||
}
|
||||
|
||||
void usart_putc(char c) {
|
||||
if (write(fd, &c, 1) != 1)
|
||||
return;
|
||||
}
|
||||
|
||||
char usart_getc(void) {
|
||||
char c;
|
||||
if (read(fd, &c, 1) != 1) return 0;
|
||||
return c;
|
||||
}
|
||||
|
||||
static void *serial_rx_thread(void *vptr_args) {
|
||||
unsigned int length;
|
||||
uint8_t * cbuf = malloc(100000);
|
||||
|
||||
// Receive loop
|
||||
while (1) {
|
||||
length = read(fd, cbuf, 300);
|
||||
if (length <= 0) {
|
||||
perror("Error: ");
|
||||
exit(1);
|
||||
}
|
||||
if (usart_callback)
|
||||
usart_callback(cbuf, length, NULL);
|
||||
}
|
||||
return NULL;
|
||||
}
|
230
thirdparty/libcsp/src/drivers/usart/usart_windows.c
vendored
Normal file
230
thirdparty/libcsp/src/drivers/usart/usart_windows.c
vendored
Normal file
@ -0,0 +1,230 @@
|
||||
#include <stdio.h>
|
||||
#include <Windows.h>
|
||||
#include <process.h>
|
||||
|
||||
#include <csp/csp.h>
|
||||
#include <csp/drivers/usart.h>
|
||||
|
||||
static HANDLE portHandle = INVALID_HANDLE_VALUE;
|
||||
static HANDLE rxThread = INVALID_HANDLE_VALUE;
|
||||
static CRITICAL_SECTION txSection;
|
||||
static LONG isListening = 0;
|
||||
static usart_callback_t usart_callback = NULL;
|
||||
|
||||
static void prvSendData(char *buf, int bufsz);
|
||||
static int prvTryOpenPort(const char* intf);
|
||||
static int prvTryConfigurePort(const struct usart_conf*);
|
||||
static int prvTrySetPortTimeouts(void);
|
||||
static const char* prvParityToStr(BYTE paritySetting);
|
||||
|
||||
#ifdef CSP_DEBUG
|
||||
static void prvPrintError(void) {
|
||||
char *messageBuffer = NULL;
|
||||
DWORD errorCode = GetLastError();
|
||||
DWORD formatMessageRet;
|
||||
formatMessageRet = FormatMessageA(
|
||||
FORMAT_MESSAGE_ALLOCATE_BUFFER |
|
||||
FORMAT_MESSAGE_FROM_SYSTEM,
|
||||
NULL,
|
||||
errorCode,
|
||||
MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
|
||||
(char*)&messageBuffer,
|
||||
0,
|
||||
NULL);
|
||||
|
||||
if( !formatMessageRet ) {
|
||||
csp_log_error("FormatMessage error, code: %lu", GetLastError());
|
||||
return;
|
||||
}
|
||||
csp_log_error("%s", messageBuffer);
|
||||
LocalFree(messageBuffer);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CSP_DEBUG
|
||||
#define printError() prvPrintError()
|
||||
#else
|
||||
#define printError() do {} while(0)
|
||||
#endif
|
||||
|
||||
static int prvTryOpenPort(const char *intf) {
|
||||
portHandle = CreateFileA(
|
||||
intf,
|
||||
GENERIC_READ|GENERIC_WRITE,
|
||||
0,
|
||||
NULL,
|
||||
OPEN_EXISTING,
|
||||
0,
|
||||
NULL);
|
||||
|
||||
if( portHandle == INVALID_HANDLE_VALUE ) {
|
||||
DWORD errorCode = GetLastError();
|
||||
if( errorCode == ERROR_FILE_NOT_FOUND ) {
|
||||
csp_log_error("Could not open serial port, because it didn't exist!");
|
||||
}
|
||||
else
|
||||
csp_log_error("Failure opening serial port! Code: %lu", errorCode);
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int prvTryConfigurePort(const struct usart_conf * conf) {
|
||||
DCB portSettings = {0};
|
||||
portSettings.DCBlength = sizeof(DCB);
|
||||
if(!GetCommState(portHandle, &portSettings) ) {
|
||||
csp_log_error("Could not get default settings for open COM port! Code: %lu", GetLastError());
|
||||
return -1;
|
||||
}
|
||||
portSettings.BaudRate = conf->baudrate;
|
||||
portSettings.Parity = conf->paritysetting;
|
||||
portSettings.StopBits = conf->stopbits;
|
||||
portSettings.fParity = conf->checkparity;
|
||||
portSettings.fBinary = TRUE;
|
||||
portSettings.ByteSize = conf->databits;
|
||||
if( !SetCommState(portHandle, &portSettings) ) {
|
||||
csp_log_error("Error when setting COM port settings! Code:%lu", GetLastError());
|
||||
return 1;
|
||||
}
|
||||
|
||||
GetCommState(portHandle, &portSettings);
|
||||
|
||||
csp_log_info("Port: %s, Baudrate: %lu, Data bits: %d, Stop bits: %d, Parity: %s",
|
||||
conf->device, conf->baudrate, conf->databits, conf->stopbits, prvParityToStr(conf->paritysetting));
|
||||
return 0;
|
||||
}
|
||||
|
||||
static const char* prvParityToStr(BYTE paritySetting) {
|
||||
static const char *parityStr[] = {
|
||||
"None",
|
||||
"Odd",
|
||||
"Even",
|
||||
"N/A"
|
||||
};
|
||||
char const *resultStr = NULL;
|
||||
|
||||
switch(paritySetting) {
|
||||
case NOPARITY:
|
||||
resultStr = parityStr[0];
|
||||
break;
|
||||
case ODDPARITY:
|
||||
resultStr = parityStr[1];
|
||||
break;
|
||||
case EVENPARITY:
|
||||
resultStr = parityStr[2];
|
||||
break;
|
||||
default:
|
||||
resultStr = parityStr[3];
|
||||
};
|
||||
return resultStr;
|
||||
}
|
||||
|
||||
static int prvTrySetPortTimeouts(void) {
|
||||
COMMTIMEOUTS timeouts = {0};
|
||||
|
||||
if( !GetCommTimeouts(portHandle, &timeouts) ) {
|
||||
csp_log_error("Error gettings current timeout settings");
|
||||
return 1;
|
||||
}
|
||||
|
||||
timeouts.ReadIntervalTimeout = 5;
|
||||
timeouts.ReadTotalTimeoutMultiplier = 1;
|
||||
timeouts.ReadTotalTimeoutConstant = 5;
|
||||
timeouts.WriteTotalTimeoutMultiplier = 1;
|
||||
timeouts.WriteTotalTimeoutConstant = 5;
|
||||
|
||||
if(!SetCommTimeouts(portHandle, &timeouts)) {
|
||||
csp_log_error("Error setting timeouts!");
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
unsigned WINAPI prvRxTask(void* params) {
|
||||
DWORD bytesRead;
|
||||
DWORD eventStatus;
|
||||
uint8_t recvBuffer[24];
|
||||
SetCommMask(portHandle, EV_RXCHAR);
|
||||
|
||||
while(isListening) {
|
||||
WaitCommEvent(portHandle, &eventStatus, NULL);
|
||||
if( !(eventStatus & EV_RXCHAR) ) {
|
||||
continue;
|
||||
}
|
||||
if( !ReadFile(portHandle, recvBuffer, 24, &bytesRead, NULL)) {
|
||||
csp_log_warn("Error receiving data! Code: %lu", GetLastError());
|
||||
continue;
|
||||
}
|
||||
if( usart_callback != NULL )
|
||||
usart_callback(recvBuffer, (size_t)bytesRead, NULL);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void prvSendData(char *buf, int bufsz) {
|
||||
DWORD bytesTotal = 0;
|
||||
DWORD bytesActual;
|
||||
if( !WriteFile(portHandle, buf, bufsz-bytesTotal, &bytesActual, NULL) ) {
|
||||
csp_log_error("Could not write data. Code: %lu", GetLastError());
|
||||
return;
|
||||
}
|
||||
if( !FlushFileBuffers(portHandle) ) {
|
||||
csp_log_warn("Could not flush write buffer. Code: %lu", GetLastError());
|
||||
}
|
||||
}
|
||||
|
||||
void usart_shutdown(void) {
|
||||
InterlockedExchange(&isListening, 0);
|
||||
CloseHandle(portHandle);
|
||||
portHandle = INVALID_HANDLE_VALUE;
|
||||
if( rxThread != INVALID_HANDLE_VALUE ) {
|
||||
WaitForSingleObject(rxThread, INFINITE);
|
||||
rxThread = INVALID_HANDLE_VALUE;
|
||||
}
|
||||
DeleteCriticalSection(&txSection);
|
||||
}
|
||||
|
||||
void usart_listen(void) {
|
||||
InterlockedExchange(&isListening, 1);
|
||||
rxThread = (HANDLE)_beginthreadex(NULL, 0, &prvRxTask, NULL, 0, NULL);
|
||||
}
|
||||
|
||||
void usart_putstr(char* buf, int bufsz) {
|
||||
EnterCriticalSection(&txSection);
|
||||
prvSendData(buf, bufsz);
|
||||
LeaveCriticalSection(&txSection);
|
||||
}
|
||||
|
||||
void usart_insert(char c, void *pxTaskWoken) {
|
||||
/* redirect debug output to stdout */
|
||||
printf("%c", c);
|
||||
}
|
||||
|
||||
void usart_set_callback(usart_callback_t callback) {
|
||||
usart_callback = callback;
|
||||
}
|
||||
|
||||
void usart_init(struct usart_conf * conf) {
|
||||
if( prvTryOpenPort(conf->device) ) {
|
||||
printError();
|
||||
return;
|
||||
}
|
||||
|
||||
if( prvTryConfigurePort(conf) ) {
|
||||
printError();
|
||||
return;
|
||||
}
|
||||
|
||||
if( prvTrySetPortTimeouts() ) {
|
||||
printError();
|
||||
return;
|
||||
}
|
||||
|
||||
InitializeCriticalSection(&txSection);
|
||||
|
||||
/* Start receiver thread */
|
||||
usart_listen();
|
||||
}
|
||||
|
||||
|
Reference in New Issue
Block a user