aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorJakob Odersky <jodersky@gmail.com>2013-06-21 17:56:03 +0200
committerJakob Odersky <jodersky@gmail.com>2013-06-21 17:56:03 +0200
commit554ba2a2227374f2078e80bca292aed02465e10f (patch)
tree616fadbaf44ff3eabc6f8f2170dfd320ce562a86
parent6b00e5a097fe8edfacc08e575487a6ed360b2889 (diff)
downloadakka-serial-554ba2a2227374f2078e80bca292aed02465e10f.tar.gz
akka-serial-554ba2a2227374f2078e80bca292aed02465e10f.tar.bz2
akka-serial-554ba2a2227374f2078e80bca292aed02465e10f.zip
implement new native layer
-rw-r--r--src/main/java/com/github/jodersky/flow/low/NativeSerial.java69
-rw-r--r--src/main/native/flow.c176
-rw-r--r--src/main/native/flow.h72
-rw-r--r--src/main/scala/com/github/jodersky/flow/SerialOperator.scala2
-rw-r--r--src/main/scala/com/github/jodersky/flow/exceptions.scala1
-rw-r--r--src/main/scala/com/github/jodersky/flow/low/Serial.scala57
6 files changed, 236 insertions, 141 deletions
diff --git a/src/main/java/com/github/jodersky/flow/low/NativeSerial.java b/src/main/java/com/github/jodersky/flow/low/NativeSerial.java
index 6bdcde5..b488d5e 100644
--- a/src/main/java/com/github/jodersky/flow/low/NativeSerial.java
+++ b/src/main/java/com/github/jodersky/flow/low/NativeSerial.java
@@ -1,49 +1,62 @@
package com.github.jodersky.flow.low;
+/** Thin layer on top of native code. */
class NativeSerial {
static {
NativeLoader.load();
}
- final static int E_PERMISSION = -1;
- final static int E_OPEN = -2;
+ final static int E_IO = -1;
+ final static int E_ACCESS_DENIED = -2;
final static int E_BUSY = -3;
- final static int E_BAUD = -4;
- final static int E_PIPE = -5;
- final static int E_MALLOC = -6;
- final static int E_POINTER = -7;
- final static int E_POLL = -8;
- final static int E_IO = -9;
- final static int E_CLOSE = -10;
-
+ final static int E_INVALID_BAUD = -4;
+ final static int E_INTERRUPT = -5;
- /* return values:
- * 0 ok
- * E_PERMISSION don't have permission to open
- * E_OPEN can't get file descriptor
- * E_BUSY device busy
- * E_BAUD invalid baudrate
- * E_PIPE can't open pipe for graceful closing
- * E_MALLOC malloc error */
+ /**Opens a serial port and allocates memory for storing configuration. Note: if this function fails,
+ * any internally allocated resources will be freed.
+ * @param port_name name of port
+ * @param baud baud rate
+ * @param serial pointer to memory that will be allocated with a serial structure
+ * @return 0 on success
+ * @return E_ACCESS_DENIED if permissions are not sufficient to open port
+ * @return E_BUSY if port is already in use
+ * @return E_INVALID_BAUD if specified baudrate is non-standard
+ * @return E_IO on other error */
native static int open(String device, int baud, long[] serial);
- /* return
- * >0 number of bytes read
- * E_POINTER invalid serial pointer
- * E_POLL poll error
- * E_IO read error
- * E_CLOSE close request */
+ /**Starts a blocking read from a previously opened serial port. The read is blocking, however it may be
+ * interrupted by calling 'serial_interrupt' on the given serial port.
+ * @param serial pointer to serial configuration from which to read
+ * @param buffer buffer into which data is read
+ * @param size maximum buffer size
+ * @return n>0 the number of bytes read into buffer
+ * @return E_INTERRUPT if the call to this function was interrupted
+ * @return E_IO on IO error */
native static int read(long serial, byte[] buffer);
- /*return
- * >0 number of bytes written
- * E_POINTER invalid serial config (null pointer)
- * E_IO write error */
+ /**Writes data to a previously opened serial port.
+ * @param serial pointer to serial configuration to which to write
+ * @param data data to write
+ * @param size number of bytes to write from data
+ * @return n>0 the number of bytes written
+ * @return E_IO on IO error */
native static int write(long serial, byte[] buffer);
+ /**Interrupts a blocked read call.
+ * @param serial_config the serial port to interrupt
+ * @return 0 on success
+ * @return E_IO on error */
+ native static int interrupt(long serial);
+
+ /**Closes a previously opened serial port and frees memory containing the configuration. Note: after a call to
+ * this function, the 'serial' pointer will become invalid, make sure you only call it once. This function is NOT
+ * thread safe, make sure no read or write is in prgress when this function is called (the reason is that per
+ * close manual page, close should not be called on a file descriptor that is in use by another thread).
+ * @param serial pointer to serial configuration that is to be closed (and freed) */
native static void close(long serial);
+ /**Sets debugging option. If debugging is enabled, detailed error message are printed from method calls. */
native static void debug(boolean value);
}
diff --git a/src/main/native/flow.c b/src/main/native/flow.c
index 24e4cb3..4353e80 100644
--- a/src/main/native/flow.c
+++ b/src/main/native/flow.c
@@ -31,59 +31,34 @@
#include <stdlib.h>
#include <stdio.h>
-#include <stdbool.h>
#include <unistd.h>
#include <errno.h>
#include <termios.h>
#include <fcntl.h>
#include <poll.h>
#include "com_github_jodersky_flow_low_NativeSerial.h"
-
-#define E_PERMISSION -1
-#define E_OPEN -2
-#define E_BUSY -3
-#define E_BAUD -4
-#define E_PIPE -5
-#define E_MALLOC -6
-#define E_POINTER -7
-#define E_POLL -8
-#define E_IO -9
-#define E_CLOSE -10
-
+#include "flow.h"
static bool debug = false;
-#define DEBUG(f) if (debug) {f;}
+#define DEBUG(f) if (debug) {f}
-//contains file descriptors used in managing a serial port
-struct serial_config {
-
- int fd; //serial port
- int pipe_read; //event
- int pipe_write; //event
-
-};
+void serial_debug(bool value) {
+ debug = value;
+}
-/* return values:
- * 0 ok
- * E_PERMISSION don't have permission to open
- * E_OPEN can't get file descriptor
- * E_BUSY device busy
- * E_BAUD invalid baudrate
- * E_PIPE can't open pipe for graceful closing
- * E_MALLOC malloc error
- */
-int serial_open(const char* device, int baud, struct serial_config** serial) {
+int serial_open(const char* port_name, int baud, struct serial_config** serial) {
- int fd = open(device, O_RDWR | O_NOCTTY | O_NONBLOCK);
+ int fd = open(port_name, O_RDWR | O_NOCTTY | O_NONBLOCK);
if (fd < 0) {
- DEBUG(perror(device));
- if (errno == EACCES) return E_PERMISSION;
- else return E_OPEN;
+ DEBUG(perror("obtain file descriptor"););
+ if (errno == EACCES) return E_ACCESS_DENIED;
+ else return E_IO;
}
if (flock(fd, LOCK_EX | LOCK_NB) < 0) {
- DEBUG(perror(device));
+ DEBUG(perror("acquire lock on port"););
+ close(fd);
return E_BUSY;
}
@@ -107,7 +82,10 @@ int serial_open(const char* device, int baud, struct serial_config** serial) {
case 57600: bd = B57600; break;
case 115200: bd = B115200; break;
case 230400: bd = B230400; break;
- default: return E_BAUD; break;
+ default:
+ close(fd);
+ return E_INVALID_BAUD;
+ break;
}
/* configure new port settings */
@@ -118,77 +96,83 @@ int serial_open(const char* device, int baud, struct serial_config** serial) {
newtio.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // make raw
newtio.c_oflag &= ~OPOST; // make raw
- // see: http://unixwiz.net/techtips/termios-vmin-vtime.html
+ //see: http://unixwiz.net/techtips/termios-vmin-vtime.html
//newtio.c_cc[VMIN] = 1;
//newtio.c_cc[VTIME] = 2*10/baud;
- cfsetspeed(&newtio, bd);
+
+ if (cfsetspeed(&newtio, bd) < 0) {
+ DEBUG(perror("set baud rate"););
+ close(fd);
+ return E_IO;
+ }
/* load new settings to port */
- tcflush(fd, TCIOFLUSH);
- tcsetattr(fd,TCSANOW,&newtio);
+ if (tcflush(fd, TCIOFLUSH) < 0) {
+ DEBUG(perror("flush serial settings"););
+ close(fd);
+ return E_IO;
+ }
+
+ if (tcsetattr(fd, TCSANOW, &newtio) < 0) {
+ DEBUG(perror("apply serial settings"););
+ close(fd);
+ return E_IO;
+ }
int pipe_fd[2];
if (pipe2(pipe_fd, O_NONBLOCK) < 0) {
- DEBUG(perror(device));
- return E_PIPE;
+ DEBUG(perror("open pipe"););
+ close(fd);
+ return E_IO;
}
struct serial_config* s = malloc(sizeof(s));
if (s == NULL) {
- return E_MALLOC;
+ DEBUG(perror("allocate memory for serial configuration"););
+ close(fd);
+ close(pipe_fd[0]);
+ close(pipe_fd[1]);
+ return E_IO;
}
- s->fd = fd;
- s->pipe_read = pipe_fd[0];
- s->pipe_write = pipe_fd[1];
+ s->port_fd = fd;
+ s->pipe_read_fd = pipe_fd[0];
+ s->pipe_write_fd = pipe_fd[1];
(*serial) = s;
return 0;
}
void serial_close(struct serial_config* serial) {
-
- if (serial == NULL) return;
-
- int data = 0xffffffff;
-
- //write to pipe to wake up any blocked read thread (self-pipe trick)
- if (write(serial->pipe_write, &data, 1) <= 0) {
- DEBUG(perror("error writing to pipe during close"))
+ if (close(serial->pipe_write_fd) < 0) {
+ DEBUG(perror("close write end of pipe"););
+ }
+ if (close(serial->pipe_read_fd) < 0) {
+ DEBUG(perror("close read end of pipe"););
}
- close(serial->pipe_write);
- close(serial->pipe_read);
-
- flock(serial->fd, LOCK_UN);
- close(serial->fd);
+ if (flock(serial->port_fd, LOCK_UN) < 0){
+ DEBUG(perror("release lock on port"););
+ }
+ if (close(serial->port_fd) < 0) {
+ DEBUG(perror("close port"););
+ }
free(serial);
}
-/* return
- * >0 number of bytes read
- * E_POINTER invalid serial pointer
- * E_POLL poll error
- * E_IO read error
- * E_CLOSE close request
- */
-int serial_read(struct serial_config* serial, unsigned char * buffer, size_t size) {
- if (serial == NULL) {
- return E_POINTER;
- }
-
+int serial_read(struct serial_config* serial, unsigned char* buffer, size_t size) {
struct pollfd polls[2];
- polls[0].fd = serial->fd; // serial poll
+ polls[0].fd = serial->port_fd; // serial poll
polls[0].events = POLLIN;
- polls[1].fd = serial->pipe_read; // pipe poll
+ polls[1].fd = serial->pipe_read_fd; // pipe poll
polls[1].events = POLLIN;
int n = poll(polls,2,-1);
if (n < 0) {
- DEBUG(perror("read"));
+ DEBUG(perror("poll"););
return E_IO;
}
@@ -197,27 +181,35 @@ int serial_read(struct serial_config* serial, unsigned char * buffer, size_t siz
//treat 0 bytes read as an error to avoid problems on disconnect
//anyway, after a poll there should be more than 0 bytes available to read
- if (r <= 0) {
- if (r < 0) DEBUG(perror("read"));
+ if (r <= 0) {
+ DEBUG(perror("read"););
return E_IO;
}
return r;
+ } else if ((polls[1].revents & POLLIN) != 0) {
+ return E_INTERRUPT;
} else {
- return E_CLOSE;
+ fputs("poll revents: unknown revents\n", stderr);
+ return E_IO;
}
}
-/*return
- * >0 number of bytes written
- * E_POINTER invalid serial config (null pointer)
- * E_IO write error
- */
-int serial_write(struct serial_config* serial, unsigned char* data, size_t size) {
- if (serial == NULL) return E_POINTER;
+int serial_interrupt(struct serial_config* serial) {
+ int data = 0xffffffff;
+
+ //write to pipe to wake up any blocked read thread (self-pipe trick)
+ if (write(serial->pipe_write_fd, &data, 1) < 0) {
+ DEBUG(perror("write to pipe for interrupt"););
+ return E_IO;
+ }
- int r = write(serial->fd, data, size);
+ return 0;
+}
+
+int serial_write(struct serial_config* serial, unsigned char* data, size_t size) {
+ int r = write(serial->port_fd, data, size);
if (r < 0) {
- DEBUG(perror("write"));
+ DEBUG(perror("write"););
return E_IO;
}
return r;
@@ -237,12 +229,12 @@ inline jlong s2j(struct serial_config* pointer) {
}
JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_low_NativeSerial_open
- (JNIEnv *env, jclass clazz, jstring device, jint baud, jlongArray jserialp)
+ (JNIEnv *env, jclass clazz, jstring port_name, jint baud, jlongArray jserialp)
{
- const char *dev = (*env)->GetStringUTFChars(env, device, 0);
+ const char *dev = (*env)->GetStringUTFChars(env, port_name, 0);
struct serial_config* serial;
int r = serial_open(dev, baud, &serial);
- (*env)->ReleaseStringUTFChars(env, device, dev);
+ (*env)->ReleaseStringUTFChars(env, port_name, dev);
long serialp = s2j(serial);
(*env)->SetLongArrayRegion(env, jserialp, 0, 1, &serialp);
@@ -287,5 +279,5 @@ JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_low_NativeSerial_write
JNIEXPORT void JNICALL Java_com_github_jodersky_flow_low_NativeSerial_debug
(JNIEnv *env, jclass clazz, jboolean value)
{
- debug = (bool) value;
+ serial_debug((bool) value);
}
diff --git a/src/main/native/flow.h b/src/main/native/flow.h
new file mode 100644
index 0000000..97eae83
--- /dev/null
+++ b/src/main/native/flow.h
@@ -0,0 +1,72 @@
+#ifndef FLOW_H
+#define FLOW_H
+
+#include <stdbool.h>
+
+//general error codes that are meant to be communicated to user
+#define E_IO -1 //I/O error (port should be closed)
+#define E_ACCESS_DENIED -2 //access denied
+#define E_BUSY -3 // port is busy
+#define E_INVALID_BAUD -4 // baud rate is not valid
+#define E_INTERRUPT -5 // not really an error, function call aborted because port is closed
+
+//contains file descriptors used in managing a serial port
+struct serial_config {
+
+ int port_fd; // file descriptor of serial port
+
+ /* a pipe is used to abort a serial read by writing something into the
+ * write end of the pipe */
+ int pipe_read_fd; // file descriptor, read end of pipe
+ int pipe_write_fd; // file descriptor, write end of pipe
+
+};
+
+/**Opens a serial port and allocates memory for storing configuration. Note: if this function fails,
+ * any internally allocated resources will be freed.
+ * @param port_name name of port
+ * @param baud baud rate
+ * @param serial pointer to memory that will be allocated with a serial structure
+ * @return 0 on success
+ * @return E_ACCESS_DENIED if permissions are not sufficient to open port
+ * @return E_BUSY if port is already in use
+ * @return E_INVALID_BAUD if specified baudrate is non-standard
+ * @return E_IO on other error */
+int serial_open(const char* port_name, int baud, struct serial_config** serial);
+
+/**Closes a previously opened serial port and frees memory containing the configuration. Note: after a call to
+ * this function, the 'serial' pointer will become invalid, make sure you only call it once. This function is NOT
+ * thread safe, make sure no read or write is in prgress when this function is called (the reason is that per
+ * close manual page, close should not be called on a file descriptor that is in use by another thread).
+ * @param serial pointer to serial configuration that is to be closed (and freed) */
+void serial_close(struct serial_config* serial);
+
+/**Starts a blocking read from a previously opened serial port. The read is blocking, however it may be
+ * interrupted by calling 'serial_interrupt' on the given serial port.
+ * @param serial pointer to serial configuration from which to read
+ * @param buffer buffer into which data is read
+ * @param size maximum buffer size
+ * @return n>0 the number of bytes read into buffer
+ * @return E_INTERRUPT if the call to this function was interrupted
+ * @return E_IO on IO error */
+int serial_read(struct serial_config* serial, unsigned char* buffer, size_t size);
+
+/**Interrupts a blocked read call.
+ * @param serial_config the serial port to interrupt
+ * @return 0 on success
+ * @return E_IO on error */
+int serial_interrupt(struct serial_config* serial);
+
+/**Writes data to a previously opened serial port. Non bocking.
+ * @param serial pointer to serial configuration to which to write
+ * @param data data to write
+ * @param size number of bytes to write from data
+ * @return n>0 the number of bytes written
+ * @return E_IO on IO error */
+int serial_write(struct serial_config* serial, unsigned char* data, size_t size);
+
+/**Sets debugging option. If debugging is enabled, detailed error message are printed from method calls. */
+void serial_debug(bool value);
+
+
+#endif /* FLOW_H */
diff --git a/src/main/scala/com/github/jodersky/flow/SerialOperator.scala b/src/main/scala/com/github/jodersky/flow/SerialOperator.scala
index 51cef39..c9f38cd 100644
--- a/src/main/scala/com/github/jodersky/flow/SerialOperator.scala
+++ b/src/main/scala/com/github/jodersky/flow/SerialOperator.scala
@@ -18,7 +18,7 @@ class SerialOperator(serial: LowSerial, handler: ActorRef) extends Actor {
private var continueReading = true
override def run() {
- Thread.currentThread().setName("flow-reader" + serial.port)
+ Thread.currentThread().setName("flow-reader " + serial.port)
while (continueReading) {
println("beginning read")
val data = ByteString(serial.read())
diff --git a/src/main/scala/com/github/jodersky/flow/exceptions.scala b/src/main/scala/com/github/jodersky/flow/exceptions.scala
index c7b2fa1..ab9392f 100644
--- a/src/main/scala/com/github/jodersky/flow/exceptions.scala
+++ b/src/main/scala/com/github/jodersky/flow/exceptions.scala
@@ -5,4 +5,5 @@ import java.io.IOException
class NoSuchPortException(message: String) extends IOException(message)
class PortInUseException(message: String) extends IOException(message)
class AccessDeniedException(message: String) extends IOException(message)
+class IllegalBaudRateException(message: String) extends IOException(message)
class PortClosingException(message: String) extends IOException(message) \ No newline at end of file
diff --git a/src/main/scala/com/github/jodersky/flow/low/Serial.scala b/src/main/scala/com/github/jodersky/flow/low/Serial.scala
index e482bf8..5a490ca 100644
--- a/src/main/scala/com/github/jodersky/flow/low/Serial.scala
+++ b/src/main/scala/com/github/jodersky/flow/low/Serial.scala
@@ -7,28 +7,41 @@ import com.github.jodersky.flow.AccessDeniedException
import com.github.jodersky.flow.NoSuchPortException
import com.github.jodersky.flow.PortInUseException
import com.github.jodersky.flow.PortClosingException
+import com.github.jodersky.flow.IllegalBaudRateException
import scala.util.Try
+
class Serial private (val port: String, private val pointer: Long) {
import NativeSerial._
+
+ /** State of current connection, required so that close may not be called multiple
+ * times and used to ensure close and read are never called at the same moment. */
+ private var _closed = false;
+ private def closed = synchronized{_closed}
+ private def closed_=(newValue: Boolean) = synchronized{_closed = newValue}
+
- def read(): Array[Byte] = synchronized {
+ def read(): Array[Byte] = {
+ if (!closed) {
+ //read
+ } else {
+ //
+ }
+
val buffer = new Array[Byte](100)
+
NativeSerial.read(pointer, buffer) match {
- case E_POINTER => throw new NullPointerException("pointer to native serial")
- case E_POLL => throw new IOException(port + ": polling")
- case E_IO => throw new IOException(port + ": reading")
- case E_CLOSE => throw new PortClosingException(port + " closing")
+ case E_INTERRUPT => throw new PortClosingException(port)
case bytes if bytes > 0 => buffer.take(bytes)
- case error => throw new IOException(s"unknown read error ${error}")
+ case error => throw new IOException(s"unknown error code: ${error}")
}
}
def write(data: Array[Byte]): Array[Byte] = {
+ //
import NativeSerial._
NativeSerial.write(pointer, data) match {
- case E_POINTER => throw new NullPointerException("pointer to native serial")
- case E_IO => throw new IOException(port + ": writing")
+ case E_IO => throw new IOException(port)
case bytes if bytes > 0 => data.take(bytes)
case error => throw new IOException(s"unknown write error ${error}")
}
@@ -41,22 +54,26 @@ class Serial private (val port: String, private val pointer: Long) {
}
object Serial {
+ import NativeSerial._
- def open(port: String, baud: Int) = synchronized {
- val pointer = new Array[Long](1)
- val result = NativeSerial.open(port, baud, pointer)
-
- import NativeSerial._
+ def except(result: Int): Int = result match {
+ case E_IO => throw new IOException("")
+ case E_ACCESS_DENIED => 0
+ case E_BUSY => 0
+ case E_INVALID_BAUD => 0
+ case E_INTERRUPT => 0
+ }
- result match {
- case E_PERMISSION => throw new AccessDeniedException(port)
- case E_OPEN => throw new NoSuchPortException(port)
+ def open(port: String, baud: Int): Serial = synchronized {
+ val pointer = new Array[Long](1)
+ NativeSerial.open(port, baud, pointer) match {
+ case E_IO => throw new IOException("")
+ case E_ACCESS_DENIED => throw new AccessDeniedException(port)
case E_BUSY => throw new PortInUseException(port)
- case E_BAUD => throw new IllegalArgumentException(s"invalid baudrate ${baud}, use standard unix values")
- case E_PIPE => throw new IOException("cannot create pipe")
- case E_MALLOC => throw new IOException("cannot allocate memory for serial port")
+ case E_INVALID_BAUD => throw new IllegalBaudRateException(baud.toString)
+ //handle no such port
case 0 => new Serial(port, pointer(0))
- case error => throw new IOException(s"unknown error ${error}")
+ case error => throw new IOException(s"unknown error code: ${error}")
}
}