From 5c94ee017051d51f51e06a61a8bc4e70a15e36da Mon Sep 17 00:00:00 2001 From: Jakob Odersky Date: Mon, 13 Jan 2014 17:40:34 +0100 Subject: enable easier cross-compilation --- .../jodersky/flow/internal/NativeSerial.java | 75 ++++ ...om_github_jodersky_flow_internal_NativeSerial.h | 79 ++++ flow/src/main/native/include/flow.h | 80 ++++ flow/src/main/native/posix/flow.c | 312 ++++++++++++++++ flow/src/main/native/windows/README | 1 + flow/src/main/native/windows/flow.c.disabled | 416 +++++++++++++++++++++ .../scala/com/github/jodersky/flow/Parity.scala | 9 + .../scala/com/github/jodersky/flow/Serial.scala | 108 ++++++ .../scala/com/github/jodersky/flow/SerialExt.scala | 10 + .../com/github/jodersky/flow/SerialManager.scala | 55 +++ .../com/github/jodersky/flow/SerialOperator.scala | 101 +++++ .../com/github/jodersky/flow/SerialSettings.scala | 11 + .../com/github/jodersky/flow/exceptions.scala | 21 ++ .../jodersky/flow/internal/InternalSerial.scala | 92 +++++ .../jodersky/flow/internal/NativeLoader.scala | 38 ++ 15 files changed, 1408 insertions(+) create mode 100644 flow/src/main/java/com/github/jodersky/flow/internal/NativeSerial.java create mode 100644 flow/src/main/native/include/com_github_jodersky_flow_internal_NativeSerial.h create mode 100644 flow/src/main/native/include/flow.h create mode 100644 flow/src/main/native/posix/flow.c create mode 100644 flow/src/main/native/windows/README create mode 100644 flow/src/main/native/windows/flow.c.disabled create mode 100644 flow/src/main/scala/com/github/jodersky/flow/Parity.scala create mode 100644 flow/src/main/scala/com/github/jodersky/flow/Serial.scala create mode 100644 flow/src/main/scala/com/github/jodersky/flow/SerialExt.scala create mode 100644 flow/src/main/scala/com/github/jodersky/flow/SerialManager.scala create mode 100644 flow/src/main/scala/com/github/jodersky/flow/SerialOperator.scala create mode 100644 flow/src/main/scala/com/github/jodersky/flow/SerialSettings.scala create mode 100644 flow/src/main/scala/com/github/jodersky/flow/exceptions.scala create mode 100644 flow/src/main/scala/com/github/jodersky/flow/internal/InternalSerial.scala create mode 100644 flow/src/main/scala/com/github/jodersky/flow/internal/NativeLoader.scala (limited to 'flow/src') diff --git a/flow/src/main/java/com/github/jodersky/flow/internal/NativeSerial.java b/flow/src/main/java/com/github/jodersky/flow/internal/NativeSerial.java new file mode 100644 index 0000000..524803e --- /dev/null +++ b/flow/src/main/java/com/github/jodersky/flow/internal/NativeSerial.java @@ -0,0 +1,75 @@ +package com.github.jodersky.flow.internal; + +import com.github.jodersky.flow.internal.NativeLoader; + +/** Thin layer on top of native code. */ +class NativeSerial { + + static { + NativeLoader.load(); + } + + final static int E_IO = -1; + final static int E_ACCESS_DENIED = -2; + final static int E_BUSY = -3; + final static int E_INVALID_SETTINGS = -4; + final static int E_INTERRUPT = -5; + final static int E_NO_PORT = -6; + + final static int PARITY_NONE = 0; + final static int PARITY_ODD = 1; + final static int PARITY_EVEN = 2; + + /**Opens a serial port and allocates memory for storing configuration. Note: if this function fails, + * any internally allocated resources will be freed. + * @param device name of port + * @param baud baud rate + * @param characterSize character size of data transmitted through serial device + * @param twoStopBits set to use two stop bits instead of one + * @param parity kind of parity checking to use + * @param serial pointer to memory that will be allocated with a serial structure + * @return 0 on success + * @return E_NO_PORT if the given port does not exist + * @return E_ACCESS_DENIED if permissions are not sufficient to open port + * @return E_BUSY if port is already in use + * @return E_INVALID_SETTINGS if any of the specified settings are not supported + * @return E_IO on other error */ + native static int open(String device, int baud, int characterSize, boolean twoStopBits, int parity, long[] 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 */ + native static int read(long serial, byte[] buffer); + + /**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) + * @return 0 on success + * @return E_IO on error */ + native static int close(long serial); + + /**Sets debugging option. If debugging is enabled, detailed error message are printed (to stderr) from method calls. */ + native static void debug(boolean value); + +} diff --git a/flow/src/main/native/include/com_github_jodersky_flow_internal_NativeSerial.h b/flow/src/main/native/include/com_github_jodersky_flow_internal_NativeSerial.h new file mode 100644 index 0000000..1c71688 --- /dev/null +++ b/flow/src/main/native/include/com_github_jodersky_flow_internal_NativeSerial.h @@ -0,0 +1,79 @@ +/* DO NOT EDIT THIS FILE - it is machine generated */ +#include +/* Header for class com_github_jodersky_flow_internal_NativeSerial */ + +#ifndef _Included_com_github_jodersky_flow_internal_NativeSerial +#define _Included_com_github_jodersky_flow_internal_NativeSerial +#ifdef __cplusplus +extern "C" { +#endif +#undef com_github_jodersky_flow_internal_NativeSerial_E_IO +#define com_github_jodersky_flow_internal_NativeSerial_E_IO -1L +#undef com_github_jodersky_flow_internal_NativeSerial_E_ACCESS_DENIED +#define com_github_jodersky_flow_internal_NativeSerial_E_ACCESS_DENIED -2L +#undef com_github_jodersky_flow_internal_NativeSerial_E_BUSY +#define com_github_jodersky_flow_internal_NativeSerial_E_BUSY -3L +#undef com_github_jodersky_flow_internal_NativeSerial_E_INVALID_SETTINGS +#define com_github_jodersky_flow_internal_NativeSerial_E_INVALID_SETTINGS -4L +#undef com_github_jodersky_flow_internal_NativeSerial_E_INTERRUPT +#define com_github_jodersky_flow_internal_NativeSerial_E_INTERRUPT -5L +#undef com_github_jodersky_flow_internal_NativeSerial_E_NO_PORT +#define com_github_jodersky_flow_internal_NativeSerial_E_NO_PORT -6L +#undef com_github_jodersky_flow_internal_NativeSerial_PARITY_NONE +#define com_github_jodersky_flow_internal_NativeSerial_PARITY_NONE 0L +#undef com_github_jodersky_flow_internal_NativeSerial_PARITY_ODD +#define com_github_jodersky_flow_internal_NativeSerial_PARITY_ODD 1L +#undef com_github_jodersky_flow_internal_NativeSerial_PARITY_EVEN +#define com_github_jodersky_flow_internal_NativeSerial_PARITY_EVEN 2L +/* + * Class: com_github_jodersky_flow_internal_NativeSerial + * Method: open + * Signature: (Ljava/lang/String;IIZI[J)I + */ +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_open + (JNIEnv *, jclass, jstring, jint, jint, jboolean, jint, jlongArray); + +/* + * Class: com_github_jodersky_flow_internal_NativeSerial + * Method: read + * Signature: (J[B)I + */ +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_read + (JNIEnv *, jclass, jlong, jbyteArray); + +/* + * Class: com_github_jodersky_flow_internal_NativeSerial + * Method: write + * Signature: (J[B)I + */ +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_write + (JNIEnv *, jclass, jlong, jbyteArray); + +/* + * Class: com_github_jodersky_flow_internal_NativeSerial + * Method: interrupt + * Signature: (J)I + */ +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_interrupt + (JNIEnv *, jclass, jlong); + +/* + * Class: com_github_jodersky_flow_internal_NativeSerial + * Method: close + * Signature: (J)I + */ +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_close + (JNIEnv *, jclass, jlong); + +/* + * Class: com_github_jodersky_flow_internal_NativeSerial + * Method: debug + * Signature: (Z)V + */ +JNIEXPORT void JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_debug + (JNIEnv *, jclass, jboolean); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/flow/src/main/native/include/flow.h b/flow/src/main/native/include/flow.h new file mode 100644 index 0000000..ebb845a --- /dev/null +++ b/flow/src/main/native/include/flow.h @@ -0,0 +1,80 @@ +#ifndef FLOW_H +#define FLOW_H + +#include + +//general error codes that are returned by functions +#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_SETTINGS -4 // some port settings are invalid +#define E_INTERRUPT -5 // not really an error, function call aborted because port is closed +#define E_NO_PORT -6 //requested port does not exist + +#define PARITY_NONE 0 +#define PARITY_ODD 1 +#define PARITY_EVEN 2 + +/** Represents an open serial port. */ +struct serial_config; + +/**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 char_size character size of data transmitted through serial device + * @param two_stop_bits set to use two stop bits instead of one + * @param parity kind of parity checking to use + * @param serial pointer to memory that will be allocated with a serial structure + * @return 0 on success + * @return E_NO_PORT if the given port does not exist + * @return E_ACCESS_DENIED if permissions are not sufficient to open port + * @return E_BUSY if port is already in use + * @return E_INVALID_SETTINGS if any of the specified settings are not supported + * @return E_IO on other error */ +int serial_open( + const char* port_name, + int baud, + int char_size, + bool two_stop_bits, + int parity, + 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) + * @return 0 on success + * @return E_IO on error */ +int serial_close(struct serial_config* serial); + +/**Starts a 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/flow/src/main/native/posix/flow.c b/flow/src/main/native/posix/flow.c new file mode 100644 index 0000000..caf7b9b --- /dev/null +++ b/flow/src/main/native/posix/flow.c @@ -0,0 +1,312 @@ +#include +#include +#include +#include +#include +#include +#include "com_github_jodersky_flow_internal_NativeSerial.h" +#include "flow.h" + +static bool debug = false; +#define DEBUG(f) if (debug) {f} + +void serial_debug(bool value) { + debug = value; +} + +//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 + +}; + +int serial_open( + const char* port_name, + int baud, + int char_size, + bool two_stop_bits, + int parity, + struct serial_config** serial) { + + int fd = open(port_name, O_RDWR | O_NOCTTY | O_NONBLOCK); + + if (fd < 0) { + int en = errno; + DEBUG(perror("obtain file descriptor");); + if (en == EACCES) return E_ACCESS_DENIED; + if (en == ENOENT) return E_NO_PORT; + return E_IO; + } + + if (flock(fd, LOCK_EX | LOCK_NB) < 0) { + DEBUG(perror("acquire lock on port");); + close(fd); + return E_BUSY; + } + + /* configure new port settings */ + struct termios newtio; + + /* following calls correspond to makeraw() */ + newtio.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL | IXON); + newtio.c_oflag &= ~OPOST; + newtio.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN); + newtio.c_cflag &= ~(CSIZE | PARENB); + + /* set speed */ + speed_t bd; + switch (baud) { + case 50: bd = B50; break; + case 75: bd = B75; break; + case 110: bd = B110; break; + case 134: bd = B134; break; + case 150: bd = B150; break; + case 200: bd = B200; break; + case 300: bd = B300; break; + case 600: bd = B600; break; + case 1200: bd = B1200; break; + case 1800: bd = B1800; break; + case 2400: bd = B2400; break; + case 4800: bd = B4800; break; + case 9600: bd = B9600; break; + case 19200: bd = B19200; break; + case 38400: bd = B38400; break; + case 57600: bd = B57600; break; + case 115200: bd = B115200; break; + case 230400: bd = B230400; break; + default: + close(fd); + return E_INVALID_SETTINGS; + } + + if (cfsetspeed(&newtio, bd) < 0) { + DEBUG(perror("set baud rate");); + close(fd); + return E_IO; + } + + /* set char size*/ + switch (char_size) { + case 5: newtio.c_cflag |= CS5; break; + case 6: newtio.c_cflag |= CS6; break; + case 7: newtio.c_cflag |= CS7; break; + case 8: newtio.c_cflag |= CS8; break; + default: + close(fd); + return E_INVALID_SETTINGS; + } + + /* use two stop bits */ + if (two_stop_bits){ + newtio.c_cflag |= CSTOPB; + } + + /* set parity */ + switch (parity) { + case PARITY_NONE: break; + case PARITY_ODD: newtio.c_cflag |= (PARENB | PARODD); break; + case PARITY_EVEN: newtio.c_cflag |= PARENB; break; + default: + close(fd); + return E_INVALID_SETTINGS; + } + + 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 (pipe(pipe_fd) < 0) { + DEBUG(perror("open pipe");); + close(fd); + return E_IO; + } + + if (fcntl(pipe_fd[0], F_SETFL, O_NONBLOCK) < 0 || fcntl(pipe_fd[1], F_SETFL, O_NONBLOCK) < 0) { + DEBUG(perror("make pipe non-blocking");); + close(fd); + return E_IO; + } + + struct serial_config* s = malloc(sizeof(s)); + if (s == NULL) { + DEBUG(perror("allocate memory for serial configuration");); + close(fd); + close(pipe_fd[0]); + close(pipe_fd[1]); + return E_IO; + } + + s->port_fd = fd; + s->pipe_read_fd = pipe_fd[0]; + s->pipe_write_fd = pipe_fd[1]; + (*serial) = s; + + return 0; +} + +int serial_close(struct serial_config* serial) { + if (close(serial->pipe_write_fd) < 0) { + DEBUG(perror("close write end of pipe");); + return E_IO; + } + if (close(serial->pipe_read_fd) < 0) { + DEBUG(perror("close read end of pipe");); + return E_IO; + } + + if (flock(serial->port_fd, LOCK_UN) < 0){ + DEBUG(perror("release lock on port");); + return E_IO; + } + if (close(serial->port_fd) < 0) { + DEBUG(perror("close port");); + return E_IO; + } + + free(serial); + return 0; +} + +int serial_read(struct serial_config* serial, unsigned char* buffer, size_t size) { + int port = serial->port_fd; + int pipe = serial->pipe_read_fd; + + fd_set rfds; + FD_ZERO(&rfds); + FD_SET(port, &rfds); + FD_SET(pipe, &rfds); + + int nfds = pipe + 1; + if (pipe < port) nfds = port + 1; + + int n = select(nfds, &rfds, NULL, NULL, NULL); + if (n < 0) { + DEBUG(perror("select");); + return E_IO; + } + + if (FD_ISSET(port, &rfds)) { + int r = read(port, buffer, size); + + //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) { + DEBUG(perror("read");); + return E_IO; + } + return r; + } else if (FD_ISSET(pipe, &rfds)) { + return E_INTERRUPT; + } else { + fputs("select: unknown read sets", stderr); + return E_IO; + } +} + +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");); + return E_IO; + } + return r; +} + +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; + } + + return 0; +} + + +// JNI bindings +// ============ + +inline struct serial_config* j2s(jlong pointer) { + return (struct serial_config*) pointer; +} + +inline jlong s2j(struct serial_config* pointer) { + return (jlong) pointer; +} + +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_open + (JNIEnv *env, jclass clazz, jstring port_name, jint baud, jint char_size, jboolean two_stop_bits, jint parity, jlongArray jserialp) +{ + const char *dev = (*env)->GetStringUTFChars(env, port_name, 0); + struct serial_config* serial; + int r = serial_open(dev, baud, char_size, two_stop_bits, parity, &serial); + (*env)->ReleaseStringUTFChars(env, port_name, dev); + + long serialp = s2j(serial); + (*env)->SetLongArrayRegion(env, jserialp, 0, 1, &serialp); + + return r; +} + +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_close + (JNIEnv * env, jclass clazz, jlong serial) +{ + serial_close(j2s(serial)); +} + +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_read + (JNIEnv * env, jclass clazz, jlong serial, jbyteArray jbuffer) +{ + + jsize size = (*env)->GetArrayLength(env, jbuffer); + + unsigned char buffer[size]; + int n = serial_read(j2s(serial), buffer, size); + if (n < 0) { + return n; + } + + (*env)->SetByteArrayRegion(env, jbuffer, 0, n, (signed char *) buffer); + return n; +} + +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_write + (JNIEnv * env, jclass clazz, jlong serial, jbyteArray jbuffer) +{ + unsigned char * buffer = (*env)->GetByteArrayElements(env, jbuffer, NULL); + int size = (*env)->GetArrayLength(env, jbuffer); + int r = serial_write(j2s(serial), buffer, size); + + (*env)->ReleaseByteArrayElements(env, jbuffer, buffer, JNI_ABORT); + + return r; +} + +JNIEXPORT jint JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_interrupt + (JNIEnv * env, jclass clazz, jlong serial) +{ + return serial_interrupt(j2s(serial)); +} + +JNIEXPORT void JNICALL Java_com_github_jodersky_flow_internal_NativeSerial_debug + (JNIEnv *env, jclass clazz, jboolean value) +{ + serial_debug((bool) value); +} diff --git a/flow/src/main/native/windows/README b/flow/src/main/native/windows/README new file mode 100644 index 0000000..3d24410 --- /dev/null +++ b/flow/src/main/native/windows/README @@ -0,0 +1 @@ +The contents of the file flow.c were found in the avrdude project. They look like they may be a good starting point for serial communication on windows. diff --git a/flow/src/main/native/windows/flow.c.disabled b/flow/src/main/native/windows/flow.c.disabled new file mode 100644 index 0000000..86a267c --- /dev/null +++ b/flow/src/main/native/windows/flow.c.disabled @@ -0,0 +1,416 @@ +/* + * avrdude - A Downloader/Uploader for AVR device programmers + * Copyright (C) 2003, 2004 Martin J. Thomas + * Copyright (C) 2006 Joerg Wunsch + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program 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 General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +/* $Id$ */ + +/* + * Native Win32 serial interface for avrdude. + */ + +#include "avrdude.h" + +#if defined(WIN32NATIVE) + +#include +#include +#include /* for isprint */ + +#include "serial.h" + +long serial_recv_timeout = 5000; /* ms */ + +#define W32SERBUFSIZE 1024 + +struct baud_mapping { + long baud; + DWORD speed; +}; + +/* HANDLE hComPort=INVALID_HANDLE_VALUE; */ + +static struct baud_mapping baud_lookup_table [] = { + { 1200, CBR_1200 }, + { 2400, CBR_2400 }, + { 4800, CBR_4800 }, + { 9600, CBR_9600 }, + { 19200, CBR_19200 }, + { 38400, CBR_38400 }, + { 57600, CBR_57600 }, + { 115200, CBR_115200 }, + { 0, 0 } /* Terminator. */ +}; + +static DWORD serial_baud_lookup(long baud) +{ + struct baud_mapping *map = baud_lookup_table; + + while (map->baud) { + if (map->baud == baud) + return map->speed; + map++; + } + + /* + * If a non-standard BAUD rate is used, issue + * a warning (if we are verbose) and return the raw rate + */ + if (verbose > 0) + fprintf(stderr, "%s: serial_baud_lookup(): Using non-standard baud rate: %ld", + progname, baud); + + return baud; +} + + +static BOOL serial_w32SetTimeOut(HANDLE hComPort, DWORD timeout) // in ms +{ + COMMTIMEOUTS ctmo; + ZeroMemory (&ctmo, sizeof(COMMTIMEOUTS)); + ctmo.ReadIntervalTimeout = timeout; + ctmo.ReadTotalTimeoutMultiplier = timeout; + ctmo.ReadTotalTimeoutConstant = timeout; + + return SetCommTimeouts(hComPort, &ctmo); +} + +static int ser_setspeed(union filedescriptor *fd, long baud) +{ + DCB dcb; + HANDLE hComPort = (HANDLE)fd->pfd; + + ZeroMemory (&dcb, sizeof(DCB)); + dcb.DCBlength = sizeof(DCB); + dcb.BaudRate = serial_baud_lookup (baud); + dcb.fBinary = 1; + dcb.fDtrControl = DTR_CONTROL_DISABLE; + dcb.fRtsControl = RTS_CONTROL_DISABLE; + dcb.ByteSize = 8; + dcb.Parity = NOPARITY; + dcb.StopBits = ONESTOPBIT; + + if (!SetCommState(hComPort, &dcb)) + return -1; + + return 0; +} + + +static int ser_open(char * port, long baud, union filedescriptor *fdp) +{ + LPVOID lpMsgBuf; + HANDLE hComPort=INVALID_HANDLE_VALUE; + char *newname = 0; + + /* + * If the port is of the form "net::", then + * handle it as a TCP connection to a terminal server. + * + * This is curently not implemented for Win32. + */ + if (strncmp(port, "net:", strlen("net:")) == 0) { + fprintf(stderr, + "%s: ser_open(): network connects are currently not" + "implemented for Win32 environments\n", + progname); + return -1; + } + + if (strncasecmp(port, "com", strlen("com")) == 0) { + + // prepend "\\\\.\\" to name, required for port # >= 10 + newname = malloc(strlen("\\\\.\\") + strlen(port) + 1); + + if (newname == 0) { + fprintf(stderr, + "%s: ser_open(): out of memory\n", + progname); + exit(1); + } + strcpy(newname, "\\\\.\\"); + strcat(newname, port); + + port = newname; + } + + hComPort = CreateFile(port, GENERIC_READ | GENERIC_WRITE, 0, NULL, + OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL, NULL); + + if (hComPort == INVALID_HANDLE_VALUE) { + FormatMessage( + FORMAT_MESSAGE_ALLOCATE_BUFFER | + FORMAT_MESSAGE_FROM_SYSTEM | + FORMAT_MESSAGE_IGNORE_INSERTS, + NULL, + GetLastError(), + MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), // Default language + (LPTSTR) &lpMsgBuf, + 0, + NULL); + fprintf(stderr, "%s: ser_open(): can't open device \"%s\": %s\n", + progname, port, (char*)lpMsgBuf); + LocalFree( lpMsgBuf ); + return -1; + } + + if (!SetupComm(hComPort, W32SERBUFSIZE, W32SERBUFSIZE)) + { + CloseHandle(hComPort); + fprintf(stderr, "%s: ser_open(): can't set buffers for \"%s\"\n", + progname, port); + return -1; + } + + fdp->pfd = (void *)hComPort; + if (ser_setspeed(fdp, baud) != 0) + { + CloseHandle(hComPort); + fprintf(stderr, "%s: ser_open(): can't set com-state for \"%s\"\n", + progname, port); + return -1; + } + + if (!serial_w32SetTimeOut(hComPort,0)) + { + CloseHandle(hComPort); + fprintf(stderr, "%s: ser_open(): can't set initial timeout for \"%s\"\n", + progname, port); + return -1; + } + + if (newname != 0) { + free(newname); + } + return 0; +} + + +static void ser_close(union filedescriptor *fd) +{ + HANDLE hComPort=(HANDLE)fd->pfd; + if (hComPort != INVALID_HANDLE_VALUE) + CloseHandle (hComPort); + + hComPort = INVALID_HANDLE_VALUE; +} + +static int ser_set_dtr_rts(union filedescriptor *fd, int is_on) +{ + HANDLE hComPort=(HANDLE)fd->pfd; + + if (is_on) { + EscapeCommFunction(hComPort, SETDTR); + EscapeCommFunction(hComPort, SETRTS); + } else { + EscapeCommFunction(hComPort, CLRDTR); + EscapeCommFunction(hComPort, CLRRTS); + } + return 0; +} + + +static int ser_send(union filedescriptor *fd, unsigned char * buf, size_t buflen) +{ + size_t len = buflen; + unsigned char c='\0'; + DWORD written; + unsigned char * b = buf; + + HANDLE hComPort=(HANDLE)fd->pfd; + + if (hComPort == INVALID_HANDLE_VALUE) { + fprintf(stderr, "%s: ser_send(): port not open\n", + progname); + exit(1); + } + + if (!len) + return 0; + + if (verbose > 3) + { + fprintf(stderr, "%s: Send: ", progname); + + while (len) { + c = *b; + if (isprint(c)) { + fprintf(stderr, "%c ", c); + } + else { + fprintf(stderr, ". "); + } + fprintf(stderr, "[%02x] ", c); + b++; + len--; + } + fprintf(stderr, "\n"); + } + + serial_w32SetTimeOut(hComPort,500); + + if (!WriteFile (hComPort, buf, buflen, &written, NULL)) { + fprintf(stderr, "%s: ser_send(): write error: %s\n", + progname, "sorry no info avail"); // TODO + exit(1); + } + + if (written != buflen) { + fprintf(stderr, "%s: ser_send(): size/send mismatch\n", + progname); + exit(1); + } + + return 0; +} + + +static int ser_recv(union filedescriptor *fd, unsigned char * buf, size_t buflen) +{ + unsigned char c; + unsigned char * p = buf; + DWORD read; + + HANDLE hComPort=(HANDLE)fd->pfd; + + if (hComPort == INVALID_HANDLE_VALUE) { + fprintf(stderr, "%s: ser_read(): port not open\n", + progname); + exit(1); + } + + serial_w32SetTimeOut(hComPort, serial_recv_timeout); + + if (!ReadFile(hComPort, buf, buflen, &read, NULL)) { + LPVOID lpMsgBuf; + FormatMessage( + FORMAT_MESSAGE_ALLOCATE_BUFFER | + FORMAT_MESSAGE_FROM_SYSTEM | + FORMAT_MESSAGE_IGNORE_INSERTS, + NULL, + GetLastError(), + MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), // Default language + (LPTSTR) &lpMsgBuf, + 0, + NULL ); + fprintf(stderr, "%s: ser_recv(): read error: %s\n", + progname, (char*)lpMsgBuf); + LocalFree( lpMsgBuf ); + exit(1); + } + + /* time out detected */ + if (read == 0) { + if (verbose > 1) + fprintf(stderr, + "%s: ser_recv(): programmer is not responding\n", + progname); + return -1; + } + + p = buf; + + if (verbose > 3) + { + fprintf(stderr, "%s: Recv: ", progname); + + while (read) { + c = *p; + if (isprint(c)) { + fprintf(stderr, "%c ", c); + } + else { + fprintf(stderr, ". "); + } + fprintf(stderr, "[%02x] ", c); + + p++; + read--; + } + fprintf(stderr, "\n"); + } + return 0; +} + + +static int ser_drain(union filedescriptor *fd, int display) +{ + // int rc; + unsigned char buf[10]; + BOOL readres; + DWORD read; + + HANDLE hComPort=(HANDLE)fd->pfd; + + if (hComPort == INVALID_HANDLE_VALUE) { + fprintf(stderr, "%s: ser_drain(): port not open\n", + progname); + exit(1); + } + + serial_w32SetTimeOut(hComPort,250); + + if (display) { + fprintf(stderr, "drain>"); + } + + while (1) { + readres=ReadFile(hComPort, buf, 1, &read, NULL); + if (!readres) { + LPVOID lpMsgBuf; + FormatMessage( + FORMAT_MESSAGE_ALLOCATE_BUFFER | + FORMAT_MESSAGE_FROM_SYSTEM | + FORMAT_MESSAGE_IGNORE_INSERTS, + NULL, + GetLastError(), + MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), // Default language + (LPTSTR) &lpMsgBuf, + 0, + NULL ); + fprintf(stderr, "%s: ser_drain(): read error: %s\n", + progname, (char*)lpMsgBuf); + LocalFree( lpMsgBuf ); + exit(1); + } + + if (read) { // data avail + if (display) fprintf(stderr, "%02x ", buf[0]); + } + else { // no more data + if (display) fprintf(stderr, " Stop + case _: Exception => Escalate + } + + def receive = { + case c @ Open(s) => Try { InternalSerial.open(s.port, s.baud, s.characterSize, s.twoStopBits, s.parity.id) } match { + case Failure(t) => sender ! CommandFailed(c, t) + case Success(serial) => { + val operator = context.actorOf(SerialOperator(serial), name = escapePortString(s.port)) + val settings = SerialSettings(serial.port, serial.baud, serial.characterSize, serial.twoStopBits, Parity(serial.parity)) + sender.tell(Opened(settings, operator), operator) + } + } + } + +} + +object SerialManager { + + private def escapePortString(port: String) = port collect { + case '/' => '-' + case c => c + } + +} \ No newline at end of file diff --git a/flow/src/main/scala/com/github/jodersky/flow/SerialOperator.scala b/flow/src/main/scala/com/github/jodersky/flow/SerialOperator.scala new file mode 100644 index 0000000..3ac50c0 --- /dev/null +++ b/flow/src/main/scala/com/github/jodersky/flow/SerialOperator.scala @@ -0,0 +1,101 @@ +package com.github.jodersky.flow + +import java.io.IOException +import com.github.jodersky.flow.internal.InternalSerial +import Serial._ +import akka.actor.Actor +import akka.actor.ActorLogging +import akka.actor.ActorRef +import akka.actor.Terminated +import akka.actor.actorRef2Scala +import akka.util.ByteString +import scala.collection.mutable.HashSet +import akka.actor.Props + +/** + * Operator associated to an open serial port. All communication with a port is done via an operator. Operators are created though the serial manager. + * @see SerialManager + */ +class SerialOperator(serial: InternalSerial) extends Actor with ActorLogging { + import SerialOperator._ + import context._ + + private val receivers = new HashSet[ActorRef] + private val receiversLock = new Object + private def tellAllReceivers(msg: Any) = receiversLock.synchronized { + receivers.foreach { receiver => + receiver ! msg + } + } + + private object Reader extends Thread { + def readLoop() = { + var continueReading = true + while (continueReading) { + try { + val data = ByteString(serial.read()) + tellAllReceivers(Received(data)) + } catch { + + //port is closing, stop thread gracefully + case ex: PortInterruptedException => { + continueReading = false + } + + //something else went wrong stop and tell actor + case ex: Exception => { + continueReading = false + self ! ReadException(ex) + } + } + } + } + + def name = this.getName() + + override def run() { + this.setName("flow-reader " + serial.port) + readLoop() + } + } + + override def preStart() = { + Reader.start() + } + + override def postStop = { + serial.close() + } + + def receive: Receive = { + + case Register(actor) => receiversLock.synchronized { + receivers += actor + } + + case Unregister(actor) => receiversLock.synchronized { + receivers -= actor + } + + case Write(data, ack) => { + val sent = serial.write(data.toArray) + if (ack != NoAck) sender ! ack + } + + case Close => { + tellAllReceivers(Closed) + context stop self + } + + //go down with reader thread + case ReadException(ex) => throw ex + + } + +} + +object SerialOperator { + private case class ReadException(ex: Exception) + + def apply(serial: InternalSerial) = Props(classOf[SerialOperator], serial) +} \ No newline at end of file diff --git a/flow/src/main/scala/com/github/jodersky/flow/SerialSettings.scala b/flow/src/main/scala/com/github/jodersky/flow/SerialSettings.scala new file mode 100644 index 0000000..a3bc5e4 --- /dev/null +++ b/flow/src/main/scala/com/github/jodersky/flow/SerialSettings.scala @@ -0,0 +1,11 @@ +package com.github.jodersky.flow + +/** + * Groups settings used in communication over a serial port. + * @param port name of serial port + * @param baud baud rate to use with serial port + * @param characterSize size of a character of the data sent through the serial port + * @param twoStopBits set to use two stop bits instead of one + * @param parity type of parity to use with serial port + */ +case class SerialSettings(port: String, baud: Int, characterSize: Int = 8, twoStopBits: Boolean = false, parity: Parity.Parity = Parity.None) \ No newline at end of file diff --git a/flow/src/main/scala/com/github/jodersky/flow/exceptions.scala b/flow/src/main/scala/com/github/jodersky/flow/exceptions.scala new file mode 100644 index 0000000..5923ba6 --- /dev/null +++ b/flow/src/main/scala/com/github/jodersky/flow/exceptions.scala @@ -0,0 +1,21 @@ +package com.github.jodersky.flow + +import java.io.IOException + +/** The requested port could not be found. */ +class NoSuchPortException(message: String) extends Exception(message) + +/** The requested port is in use by someone else. */ +class PortInUseException(message: String) extends Exception(message) + +/** Permissions are not sufficient to open a serial port. */ +class AccessDeniedException(message: String) extends Exception(message) + +/** The settings specified are invalid. */ +class InvalidSettingsException(message: String) extends Exception(message) + +/** A blocking operation on a port was interrupted, most likely indicating that the port is closing. */ +class PortInterruptedException(message: String) extends Exception(message) + +/** The specified port has been closed. */ +class PortClosedException(message: String) extends Exception(message) \ No newline at end of file diff --git a/flow/src/main/scala/com/github/jodersky/flow/internal/InternalSerial.scala b/flow/src/main/scala/com/github/jodersky/flow/internal/InternalSerial.scala new file mode 100644 index 0000000..e69f91a --- /dev/null +++ b/flow/src/main/scala/com/github/jodersky/flow/internal/InternalSerial.scala @@ -0,0 +1,92 @@ +package com.github.jodersky.flow.internal + +import java.io.IOException +import com.github.jodersky.flow._ +import java.util.concurrent.atomic.AtomicBoolean + +/** Wraps `NativeSerial` in a more object-oriented style, still quite low level. */ +class InternalSerial private (val port: String, val baud: Int, val characterSize: Int, val twoStopBits: Boolean, val parity: Int, private val pointer: Long) { + import InternalSerial._ + + private val reading = new AtomicBoolean(false) + private val writing = new AtomicBoolean(false) + private val closed = new AtomicBoolean(false) + + /** Closes the underlying serial connection. Any threads blocking on read or write will return. */ + def close(): Unit = synchronized { + if (!closed.get()) { + closed.set(true) + except(NativeSerial.interrupt(pointer), port) + if (writing.get()) wait() + if (reading.get()) wait() + except(NativeSerial.close(pointer), port) + } + } + + /** + * Read data from underlying serial connection. + * @throws PortInterruptedException if port is closed from another thread + */ + def read(): Array[Byte] = if (!closed.get) { + reading.set(true) + try { + val buffer = new Array[Byte](100) + val bytesRead = except(NativeSerial.read(pointer, buffer), port) + buffer take bytesRead + } finally { + synchronized { + reading.set(false) + if (closed.get) notify() + } + } + } else { + throw new PortClosedException(s"port ${port} is already closed") + } + + /** + * Write data to underlying serial connection. + * @throws PortInterruptedException if port is closed from another thread + */ + def write(data: Array[Byte]): Array[Byte] = if (!closed.get) { + writing.set(true) + try { + val bytesWritten = except(NativeSerial.write(pointer, data), port) + data take bytesWritten + } finally { + synchronized { + writing.set(false) + if (closed.get) notify() + } + } + } else { + throw new PortClosedException(s"port ${port} is already closed") + } + +} + +object InternalSerial { + import NativeSerial._ + + /** Transform error code to exception if necessary. */ + private def except(result: Int, port: String): Int = result match { + case E_IO => throw new IOException(port) + case E_ACCESS_DENIED => throw new AccessDeniedException(port) + case E_BUSY => throw new PortInUseException(port) + case E_INVALID_SETTINGS => throw new InvalidSettingsException("the provided settings are invalid: be sure to use standard baud rate, character size and parity.") + case E_INTERRUPT => throw new PortInterruptedException(port) + case E_NO_PORT => throw new NoSuchPortException(port) + case error if error < 0 => throw new IOException(s"unknown error code: ${error}") + case success => success + } + + /** Open a new connection to a serial port. */ + def open(port: String, baud: Int, characterSize: Int, twoStopBits: Boolean, parity: Int): InternalSerial = synchronized { + val pointer = new Array[Long](1) + except(NativeSerial.open(port, baud, characterSize, twoStopBits, parity, pointer), port) + new InternalSerial(port, baud, characterSize, twoStopBits, parity, pointer(0)) + } + + /** Set debugging for all serial connections. Debugging results in printing extra messages from the native library in case of errors. */ + def debug(value: Boolean) = NativeSerial.debug(value) + +} \ No newline at end of file diff --git a/flow/src/main/scala/com/github/jodersky/flow/internal/NativeLoader.scala b/flow/src/main/scala/com/github/jodersky/flow/internal/NativeLoader.scala new file mode 100644 index 0000000..034be96 --- /dev/null +++ b/flow/src/main/scala/com/github/jodersky/flow/internal/NativeLoader.scala @@ -0,0 +1,38 @@ +package com.github.jodersky.flow.internal + +import java.io.File +import java.io.FileOutputStream +import scalax.file.Path +import scalax.io.Resource +import scala.util.Try + +/** Handles loading of the current platform's native library for flow. */ +object NativeLoader { + + def extract(): Option[File] = { + val os = System.getProperty("os.name").toLowerCase.filter(_ != ' ') + val arch = System.getProperty("os.arch").toLowerCase + val fqlib = System.mapLibraryName("flow") //fully qualified library name + + val in = NativeLoader.getClass().getResourceAsStream(s"/native/${arch}-${os}/${fqlib}") + if (in == null) return None + + val temp = Path.createTempFile() + Resource.fromInputStream(in).copyDataTo(temp) + temp.fileOption + } + + def loadFromJar() = extract() match { + case Some(file) => System.load(file.getAbsolutePath) + case None => throw new UnsatisfiedLinkError("cannot extract native library, the native library may not exist for your specific os/architecture combination") + } + + def load = { + try { + System.loadLibrary("flow") + } catch { + case ex: UnsatisfiedLinkError => loadFromJar() + } + } + +} \ No newline at end of file -- cgit v1.2.3