aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorPaul Selkirk <paul@psgd.org>2016-06-02 12:37:33 -0400
committerPaul Selkirk <paul@psgd.org>2016-06-02 12:37:33 -0400
commit63fd94a724893152592b5f318e7d98f2be0ede74 (patch)
treeba2376991437485ec3786f11071025d299ca404b
parentb83f77f5517d65c11052ab11e48b56dcb9f712ef (diff)
Refactor serial and slip.
-rw-r--r--rpc_client_serial.c56
-rw-r--r--rpc_serial.c109
-rw-r--r--rpc_server_serial.c26
-rw-r--r--serial_internal.h43
-rw-r--r--slip.c208
-rw-r--r--slip_internal.h22
6 files changed, 283 insertions, 181 deletions
diff --git a/rpc_client_serial.c b/rpc_client_serial.c
index 5194793..ec53e05 100644
--- a/rpc_client_serial.c
+++ b/rpc_client_serial.c
@@ -47,70 +47,22 @@
#define DEVICE "/dev/ttyUSB0"
#define SPEED B115200
-static int fd = -1;
-
hal_error_t hal_rpc_client_transport_init(void)
{
- struct termios tty;
-
- fd = open(DEVICE, O_RDWR | O_NOCTTY | O_SYNC);
- if (fd == -1)
- return perror("open"), HAL_ERROR_RPC_TRANSPORT;
-
- if (tcgetattr (fd, &tty) != 0)
- return perror("tcgetattr"), HAL_ERROR_RPC_TRANSPORT;
-
- cfsetospeed (&tty, SPEED);
- cfsetispeed (&tty, SPEED);
-
- tty.c_cflag &= ~CSIZE;
- tty.c_cflag |= (CS8 | CLOCAL | CREAD);
-
- tty.c_iflag = 0;
- tty.c_oflag = 0;
- tty.c_lflag = 0;
-
- tty.c_cc[VMIN] = 1;
- tty.c_cc[VTIME] = 0;
-
- if (tcsetattr (fd, TCSANOW, &tty) != 0)
- return perror("tcsetattr"), HAL_ERROR_RPC_TRANSPORT;
-
- return HAL_OK;
+ return hal_serial_init(DEVICE, SPEED);
}
hal_error_t hal_rpc_client_transport_close(void)
{
- int ret = close(fd);
- fd = -1;
- if (ret != 0)
- return perror("close"), HAL_ERROR_RPC_TRANSPORT;
- return HAL_OK;
+ return hal_serial_close();
}
hal_error_t hal_rpc_send(const uint8_t * const buf, const size_t len)
{
- if (hal_slip_send(buf, len) == -1)
- return HAL_ERROR_RPC_TRANSPORT;
- return HAL_OK;
+ return hal_slip_send(buf, len);
}
hal_error_t hal_rpc_recv(uint8_t * const buf, size_t * const len)
{
- int ret;
-
- if ((ret = hal_slip_recv(buf, *len)) == -1)
- return HAL_ERROR_RPC_TRANSPORT;
- *len = ret;
- return HAL_OK;
-}
-
-int hal_slip_send_char(const uint8_t c)
-{
- return write(fd, &c, 1);
-}
-
-int hal_slip_recv_char(uint8_t * const c)
-{
- return read(fd, c, 1);
+ return hal_slip_recv(buf, *len);
}
diff --git a/rpc_serial.c b/rpc_serial.c
new file mode 100644
index 0000000..dc5821f
--- /dev/null
+++ b/rpc_serial.c
@@ -0,0 +1,109 @@
+/*
+ * rpc_serial.c
+ * ------------
+ * Remote procedure call transport over serial line with SLIP framing.
+ *
+ * Copyright (c) 2016, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <stdio.h>
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <termios.h>
+#include <unistd.h>
+#include <fcntl.h>
+
+#include "hal.h"
+#include "hal_internal.h"
+#include "slip_internal.h"
+
+static int fd = -1;
+
+hal_error_t hal_serial_init(const char * const device, const speed_t speed)
+{
+ struct termios tty;
+
+ fd = open(device, O_RDWR | O_NOCTTY | O_SYNC);
+ if (fd == -1) {
+ fprintf(stderr, "open %s: ", device);
+ return perror(""), HAL_ERROR_RPC_TRANSPORT;
+ }
+
+ if (tcgetattr (fd, &tty) != 0)
+ return perror("tcgetattr"), HAL_ERROR_RPC_TRANSPORT;
+
+ cfsetospeed (&tty, speed);
+ cfsetispeed (&tty, speed);
+
+ tty.c_cflag &= ~CSIZE;
+ tty.c_cflag |= (CS8 | CLOCAL | CREAD);
+
+ tty.c_iflag = 0;
+ tty.c_oflag = 0;
+ tty.c_lflag = 0;
+
+ tty.c_cc[VMIN] = 1;
+ tty.c_cc[VTIME] = 0;
+
+ if (tcsetattr (fd, TCSANOW, &tty) != 0)
+ return perror("tcsetattr"), HAL_ERROR_RPC_TRANSPORT;
+
+ return HAL_OK;
+}
+
+hal_error_t hal_serial_close(void)
+{
+ int ret = close(fd);
+ fd = -1;
+ if (ret != 0)
+ return perror("close"), HAL_ERROR_RPC_TRANSPORT;
+ return HAL_OK;
+}
+
+hal_error_t hal_serial_send_char(const uint8_t c)
+{
+ if (write(fd, &c, 1) != 1)
+ return perror("write"), HAL_ERROR_RPC_TRANSPORT;
+ return HAL_OK;
+}
+
+hal_error_t hal_serial_recv_char(uint8_t * const c)
+{
+ if (read(fd, c, 1) != 1)
+ return perror("read"), HAL_ERROR_RPC_TRANSPORT;
+ return HAL_OK;
+}
+
+/* Access routine for the file descriptor, so daemon can poll on it.
+ */
+int hal_serial_get_fd(void)
+{
+ return fd;
+}
diff --git a/rpc_server_serial.c b/rpc_server_serial.c
index 8844f3c..f09fdc2 100644
--- a/rpc_server_serial.c
+++ b/rpc_server_serial.c
@@ -36,11 +36,6 @@
#include "hal_internal.h"
#include "slip_internal.h"
-/* Don't include stm-uart.h to avoid conflicting definitions of HAL_OK.
- */
-extern int uart_send_char(uint8_t ch);
-extern int uart_recv_char(uint8_t *cp);
-
hal_error_t hal_rpc_server_transport_init(void)
{
return HAL_OK;
@@ -53,27 +48,10 @@ hal_error_t hal_rpc_server_transport_close(void)
hal_error_t hal_rpc_sendto(const uint8_t * const buf, const size_t len, void *opaque)
{
- if (hal_slip_send(buf, len) == -1)
- return HAL_ERROR_RPC_TRANSPORT;
- return HAL_OK;
+ return hal_slip_send(buf, len);
}
hal_error_t hal_rpc_recvfrom(uint8_t * const buf, size_t * const len, void **opaque)
{
- int ret;
-
- if ((ret = hal_slip_recv(buf, *len)) == -1)
- return HAL_ERROR_RPC_TRANSPORT;
- *len = ret;
- return HAL_OK;
-}
-
-int hal_slip_send_char(uint8_t c)
-{
- return (uart_send_char(c) == 0) ? 0 : -1;
-}
-
-int hal_slip_recv_char(uint8_t *c)
-{
- return (uart_recv_char(c) == 0) ? 0 : -1;
+ return hal_slip_recv(buf, len, *len);
}
diff --git a/serial_internal.h b/serial_internal.h
new file mode 100644
index 0000000..abf2259
--- /dev/null
+++ b/serial_internal.h
@@ -0,0 +1,43 @@
+/*
+ * serial_internal.c
+ * -----------------
+ * Low-level serial transport functions.
+ *
+ * Copyright (c) 2016, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _HAL_SERIAL_INTERNAL_H
+#define _HAL_SERIAL_INTERNAL_H
+
+hal_error_t hal_serial_init(const char * const device, const speed_t speed, int * const fdp);
+hal_error_t hal_serial_close(void);
+int hal_serial_send_char(const uint8_t c);
+int hal_serial_recv_char(uint8_t * const c);
+
+#endif /* _HAL_SERIAL_INTERNAL_H */
diff --git a/slip.c b/slip.c
index 3b448f4..889663a 100644
--- a/slip.c
+++ b/slip.c
@@ -1,4 +1,37 @@
-/* SLIP send/recv code, from RFC 1055 */
+/*
+ * slip.c
+ * ------
+ * SLIP send/recv code, based on RFC 1055
+ *
+ * Copyright (c) 2016, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
#include <stdio.h> /* perror */
@@ -11,16 +44,34 @@
#define ESC_END 0334 /* ESC ESC_END means END data byte */
#define ESC_ESC 0335 /* ESC ESC_ESC means ESC data byte */
-/* SLIP_SEND: sends a packet of length "len", starting at
- * location "p".
+#define check_send_char(c) \
+ if (hal_serial_send_char(c) != HAL_OK) \
+ return perror("hal_serial_send_char"), HAL_ERROR_RPC_TRANSPORT;
+
+/* Send a single character with SLIP escaping.
*/
-int hal_slip_send(const uint8_t * const ptr, const size_t len)
+hal_error_t hal_slip_send_char(const uint8_t c)
{
- int i;
- uint8_t *p = (uint8_t *)ptr;
+ switch (c) {
+ case END:
+ check_send_char(ESC);
+ check_send_char(ESC_END);
+ break;
+ case ESC:
+ check_send_char(ESC);
+ check_send_char(ESC_ESC);
+ break;
+ default:
+ check_send_char(c);
+ }
-#define check_send_char(c) if (hal_slip_send_char(c) == -1) return perror("write"), -1;
+ return HAL_OK;
+}
+/* Send a message with SLIP framing.
+ */
+hal_error_t hal_slip_send(const uint8_t * const buf, const size_t len)
+{
/* send an initial END character to flush out any data that may
* have accumulated in the receiver due to line noise
*/
@@ -29,113 +80,74 @@ int hal_slip_send(const uint8_t * const ptr, const size_t len)
/* for each byte in the packet, send the appropriate character
* sequence
*/
- for (i = 0; i < len; ++i) {
- switch (*p) {
- /* if it's the same code as an END character, we send a
- * special two character code so as not to make the
- * receiver think we sent an END
- */
- case END:
- check_send_char(ESC);
- check_send_char(ESC_END);
- break;
-
- /* if it's the same code as an ESC character,
- * we send a special two character code so as not
- * to make the receiver think we sent an ESC
- */
- case ESC:
- check_send_char(ESC);
- check_send_char(ESC_ESC);
- break;
-
- /* otherwise, we just send the character
- */
- default:
- check_send_char(*p);
- }
-
- p++;
+ for (int i = 0; i < len; ++i) {
+ hal_error_t ret;
+ if ((ret = hal_slip_send_char(buf[i])) != HAL_OK)
+ return ret;
}
/* tell the receiver that we're done sending the packet
*/
check_send_char(END);
- return 0;
-#undef check_send_char
+ return HAL_OK;
}
-/* SLIP_RECV: receives a packet into the buffer located at "p".
- * If more than len bytes are received, the packet will
- * be truncated.
- * Returns the number of bytes stored in the buffer.
+#define check_recv_char(c) \
+ if (hal_serial_recv_char(c) != HAL_OK) \
+ return perror("hal_serial_recv_char"), HAL_ERROR_RPC_TRANSPORT;
+
+/* Receive a single character into a buffer, with SLIP un-escaping
*/
-int hal_slip_recv(uint8_t * const p, const size_t len)
+hal_error_t hal_slip_recv_char(uint8_t * const buf, size_t * const len, const size_t maxlen, int * const complete)
{
+#define buf_push(c) do { if (*len < maxlen) buf[(*len)++] = c; } while (0)
+ static int esc_flag = 0;
uint8_t c;
- size_t received = 0;
-
-#define check_recv_char(c) if (hal_slip_recv_char(&c) == -1) return perror("read"), -1;
-
- /* sit in a loop reading bytes until we put together
- * a whole packet.
- * Make sure not to copy them into the packet if we
- * run out of room.
- */
- while (1) {
- /* get a character to process
- */
- check_recv_char(c);
-
- /* handle bytestuffing if necessary
- */
- switch (c) {
-
- /* if it's an END character then we're done with
- * the packet
- */
- case END:
- /* a minor optimization: if there is no
- * data in the packet, ignore it. This is
- * meant to avoid bothering IP with all
- * the empty packets generated by the
- * duplicate END characters which are in
- * turn sent to try to detect line noise.
- */
- if (received)
- return received;
- else
- break;
-
- /* if it's the same code as an ESC character, wait
- * and get another character and then figure out
- * what to store in the packet based on that.
- */
- case ESC:
- check_recv_char(c);
-
- /* if "c" is not one of these two, then we
- * have a protocol violation. The best bet
- * seems to be to leave the byte alone and
- * just stuff it into the packet
- */
- switch(c) {
+ hal_error_t ret = hal_serial_recv_char(&c);
+ if (ret != HAL_OK)
+ return perror("hal_slip_recv_char"), ret;
+ *complete = 0;
+ switch (c) {
+ case END:
+ if (*len)
+ *complete = 1;
+ break;
+ case ESC:
+ esc_flag = 1;
+ break;
+ default:
+ if (esc_flag) {
+ esc_flag = 0;
+ switch (c) {
case ESC_END:
- c = END;
+ buf_push(END);
break;
case ESC_ESC:
- c = ESC;
+ buf_push(ESC);
break;
+ default:
+ buf_push(c);
}
-
- /* here we fall into the default handler and let
- * it store the character for us
- */
- default:
- if (received < len)
- p[received++] = c;
}
+ else {
+ buf_push(c);
+ }
+ break;
+ }
+ return HAL_OK;
+}
+
+/* Receive a message with SLIP framing, blocking mode.
+ */
+hal_error_t hal_slip_recv(uint8_t * const buf, size_t * const len, const size_t maxlen)
+{
+ int complete;
+ hal_error_t ret;
+
+ while (1) {
+ ret = hal_slip_recv_char(buf, len, maxlen, &complete);
+ if ((ret != HAL_OK) || complete)
+ return ret;
}
-#undef check_recv_char
}
diff --git a/slip_internal.h b/slip_internal.h
index 103f72d..e3b7af0 100644
--- a/slip_internal.h
+++ b/slip_internal.h
@@ -37,15 +37,23 @@
#include "hal_internal.h"
-/* Defined in slip.c - send/recv a block of data with SLIP framing.
+/* Defined in slip.c - send/recv serial data with SLIP framing.
*/
-extern int hal_slip_send(const uint8_t * const p, const size_t len);
-extern int hal_slip_recv(uint8_t * const p, const size_t len);
+extern hal_error_t hal_slip_send_char(const uint8_t c);
+extern hal_error_t hal_slip_send(const uint8_t * const buf, const size_t len);
+extern hal_error_t hal_slip_recv_char(uint8_t * const buf, size_t * const len, const size_t maxlen, int * const complete);
+extern hal_error_t hal_slip_recv(uint8_t * const buf, size_t * const len, const size_t maxlen);
-/* Defined in rpc_[client|server]_serial.c - send/recv one byte over a
- * serial connection.
+/* Defined in rpc_serial.c - send/recv one byte over a serial connection.
*/
-extern int hal_slip_send_char(const uint8_t c);
-extern int hal_slip_recv_char(uint8_t * const c);
+extern hal_error_t hal_serial_send_char(const uint8_t c);
+extern hal_error_t hal_serial_recv_char(uint8_t * const c);
+
+#ifndef STM32F4XX
+#include <termios.h> /* speed_t */
+extern hal_error_t hal_serial_init(const char * const device, const speed_t speed);
+extern hal_error_t hal_serial_close(void);
+extern int hal_serial_get_fd(void);
+#endif
#endif /* _HAL_SLIP_INTERNAL_H */