diff --git a/src/cpp/_nix_based/jssc.cpp b/src/cpp/_nix_based/jssc.cpp
new file mode 100644
index 0000000..149a6e1
--- /dev/null
+++ b/src/cpp/_nix_based/jssc.cpp
@@ -0,0 +1,819 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+#include
+#include
+#include
+#include
+#include
+#include
+#include //-D_TS_ERRNO use for Solaris C++ compiler
+
+#ifdef __linux__
+ #include
+#endif
+#ifdef __SunOS
+ #include //Needed for FIONREAD in Solaris
+#endif
+#ifdef __APPLE__
+ #include //Needed for IOSSIOSPEED in Mac OS X (Non standard baudrate)
+#endif
+
+#include
+#include "jssc_SerialNativeInterface.h"
+
+//#include //-lCstd use for Solaris linker
+
+
+/* OK */
+/* Port opening */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_openPort(JNIEnv *env, jobject object, jstring portName){
+ const char* port = env->GetStringUTFChars(portName, JNI_FALSE);
+ jint hComm;
+ hComm = open(port, O_RDWR | O_NOCTTY | O_NDELAY);
+ if(hComm != -1){
+ #if defined TIOCEXCL && !defined __SunOS
+ ioctl(hComm, TIOCEXCL);//since 0.9
+ #endif
+ int flags = fcntl(hComm, F_GETFL, 0);
+ flags &= ~O_NDELAY;
+ fcntl(hComm, F_SETFL, flags);
+ }
+ else {//since 0.9 ->
+ if(errno == EBUSY){//Port busy
+ hComm = -1;
+ }
+ else if(errno == ENOENT){//Port not found
+ hComm = -2;
+ }
+ }//<- since 0.9
+ env->ReleaseStringUTFChars(portName, port);
+ return hComm;
+}
+
+/* OK */
+/*
+ * Choose baudrate
+ */
+speed_t getBaudRateByNum(jint baudRate) {
+ switch(baudRate){
+ case 0:
+ return B0;
+ case 50:
+ return B50;
+ case 75:
+ return B75;
+ case 110:
+ return B110;
+ case 134:
+ return B134;
+ case 150:
+ return B150;
+ case 200:
+ return B200;
+ case 300:
+ return B300;
+ case 600:
+ return B600;
+ case 1200:
+ return B1200;
+ case 1800:
+ return B1800;
+ case 2400:
+ return B2400;
+ case 4800:
+ return B4800;
+ case 9600:
+ return B9600;
+ case 19200:
+ return B19200;
+ case 38400:
+ return B38400;
+ #ifdef B57600
+ case 57600:
+ return B57600;
+ #endif
+ #ifdef B115200
+ case 115200:
+ return B115200;
+ #endif
+ #ifdef B230400
+ case 230400:
+ return B230400;
+ #endif
+ #ifdef B460800
+ case 460800:
+ return B460800;
+ #endif
+
+ #ifdef B500000
+ case 500000:
+ return B500000;
+ #endif
+ #ifdef B576000
+ case 576000:
+ return B576000;
+ #endif
+ #ifdef B921600
+ case 921600:
+ return B921600;
+ #endif
+ #ifdef B1000000
+ case 1000000:
+ return B1000000;
+ #endif
+
+ #ifdef B1152000
+ case 1152000:
+ return B1152000;
+ #endif
+ #ifdef B1500000
+ case 1500000:
+ return B1500000;
+ #endif
+ #ifdef B2000000
+ case 2000000:
+ return B2000000;
+ #endif
+ #ifdef B2500000
+ case 2500000:
+ return B2500000;
+ #endif
+
+ #ifdef B3000000
+ case 3000000:
+ return B3000000;
+ #endif
+ #ifdef B3500000
+ case 3500000:
+ return B3500000;
+ #endif
+ #ifdef B4000000
+ case 4000000:
+ return B4000000;
+ #endif
+ default:
+ return -1;
+ }
+}
+
+/* OK */
+/*
+ * Choose data bits
+ */
+int getDataBitsByNum(jint byteSize) {
+ switch(byteSize){
+ case 5:
+ return CS5;
+ case 6:
+ return CS6;
+ case 7:
+ return CS7;
+ case 8:
+ return CS8;
+ default:
+ return -1;
+ }
+}
+
+/* OK */
+/*
+ * Set serial port settings
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setParams
+ (JNIEnv *env, jobject object, jint portHandle, jint baudRate, jint byteSize, jint stopBits, jint parity, jboolean setRTS, jboolean setDTR){
+ jboolean returnValue = JNI_FALSE;
+
+ speed_t baudRateValue = getBaudRateByNum(baudRate);
+ int dataBits = getDataBitsByNum(byteSize);
+
+ termios *settings = new termios();
+ if(tcgetattr(portHandle, settings) == 0){
+ if(baudRateValue != -1){
+ //Set standart baudrate from "termios.h"
+ if(cfsetispeed(settings, baudRateValue) < 0 || cfsetospeed(settings, baudRateValue) < 0){
+ goto methodEnd;
+ }
+ }
+ else {
+ #ifdef __SunOS
+ goto methodEnd;//Solaris don't support non standart baudrates
+ #elif defined __linux__
+ //Try to calculate a divisor for setting non standart baudrate
+ serial_struct *serial_info = new serial_struct();
+ if(ioctl(portHandle, TIOCGSERIAL, serial_info) < 0){ //Getting serial_info structure
+ delete serial_info;
+ goto methodEnd;
+ }
+ else {
+ serial_info->flags |= ASYNC_SPD_CUST;
+ serial_info->custom_divisor = (serial_info->baud_base/baudRate); //Calculate divisor
+ if(serial_info->custom_divisor == 0){ //If divisor == 0 go to method end to prevent "division by zero" error
+ delete serial_info;
+ goto methodEnd;
+ }
+ settings->c_cflag |= B38400;
+ if(cfsetispeed(settings, B38400) < 0 || cfsetospeed(settings, B38400) < 0){
+ delete serial_info;
+ goto methodEnd;
+ }
+ if(ioctl(portHandle, TIOCSSERIAL, serial_info) < 0){//Try to set new settings with non standart baudrate
+ delete serial_info;
+ goto methodEnd;
+ }
+ delete serial_info;
+ }
+ #endif
+ }
+ }
+
+ /*
+ * Setting data bits
+ */
+ if(dataBits != -1){
+ settings->c_cflag &= ~CSIZE;
+ settings->c_cflag |= dataBits;
+ }
+ else {
+ goto methodEnd;
+ }
+
+ /*
+ * Setting stop bits
+ */
+ if(stopBits == 0){ //1 stop bit (for info see ->> MSDN)
+ settings->c_cflag &= ~CSTOPB;
+ }
+ else if((stopBits == 1) || (stopBits == 2)){ //1 == 1.5 stop bits; 2 == 2 stop bits (for info see ->> MSDN)
+ settings->c_cflag |= CSTOPB;
+ }
+ else {
+ goto methodEnd;
+ }
+
+ settings->c_cflag |= (CREAD | CLOCAL);
+ settings->c_cflag &= ~CRTSCTS;
+ settings->c_lflag &= ~(ICANON | ECHO | ECHOE | ECHOK | ECHONL | ECHOCTL | ECHOPRT | ECHOKE | ISIG | IEXTEN);
+
+ settings->c_iflag &= ~(IXON | IXOFF | IXANY | INPCK | PARMRK | ISTRIP | IGNBRK | BRKINT | INLCR | IGNCR| ICRNL);
+#ifdef IUCLC
+ settings->c_iflag &= ~IUCLC;
+#endif
+ settings->c_oflag &= ~OPOST;
+
+ //since 0.9 ->
+ settings->c_cc[VMIN] = 0;
+ settings->c_cc[VTIME] = 0;
+ //<- since 0.9
+
+ /*
+ * Parity bits
+ */
+#ifdef PAREXT
+ settings->c_cflag &= ~(PARENB | PARODD | PAREXT);//Clear parity settings
+#elif defined CMSPAR
+ settings->c_cflag &= ~(PARENB | PARODD | CMSPAR);//Clear parity settings
+#else
+ settings->c_cflag &= ~(PARENB | PARODD);//Clear parity settings
+#endif
+ if(parity == 1){//Parity ODD
+ settings->c_cflag |= (PARENB | PARODD);
+ settings->c_iflag |= INPCK;
+ }
+ else if(parity == 2){//Parity EVEN
+ settings->c_cflag |= PARENB;
+ settings->c_iflag |= INPCK;
+ }
+ else if(parity == 3){//Parity MARK
+ #ifdef PAREXT
+ settings->c_cflag |= (PARENB | PARODD | PAREXT);
+ settings->c_iflag |= INPCK;
+ #elif defined CMSPAR
+ settings->c_cflag |= (PARENB | PARODD | CMSPAR);
+ settings->c_iflag |= INPCK;
+ #endif
+ }
+ else if(parity == 4){//Parity SPACE
+ #ifdef PAREXT
+ settings->c_cflag |= (PARENB | PAREXT);
+ settings->c_iflag |= INPCK;
+ #elif defined CMSPAR
+ settings->c_cflag |= (PARENB | CMSPAR);
+ settings->c_iflag |= INPCK;
+ #endif
+ }
+ else if(parity == 0){
+ //Do nothing (Parity NONE)
+ }
+ else {
+ goto methodEnd;
+ }
+
+ if(tcsetattr(portHandle, TCSANOW, settings) == 0){//Try to set all settings
+ #ifdef __APPLE__
+ //Try to set non-standard baud rate in Mac OS X
+ if(baudRateValue == -1){
+ speed_t speed = (speed_t)baudRate;
+ if(ioctl(portHandle, IOSSIOSPEED, &speed) < 0){//IOSSIOSPEED must be used only after tcsetattr
+ goto methodEnd;
+ }
+ }
+ #endif
+ int lineStatus;
+ if(ioctl(portHandle, TIOCMGET, &lineStatus) >= 0){
+ if(setRTS == JNI_TRUE){
+ lineStatus |= TIOCM_RTS;
+ }
+ else {
+ lineStatus &= ~TIOCM_RTS;
+ }
+ if(setDTR == JNI_TRUE){
+ lineStatus |= TIOCM_DTR;
+ }
+ else {
+ lineStatus &= ~TIOCM_DTR;
+ }
+ if(ioctl(portHandle, TIOCMSET, &lineStatus) >= 0){
+ returnValue = JNI_TRUE;
+ }
+ }
+ }
+ methodEnd: {
+ delete settings;
+ return returnValue;
+ }
+}
+
+const jint PURGE_RXABORT = 0x0002; //ignored
+const jint PURGE_RXCLEAR = 0x0008;
+const jint PURGE_TXABORT = 0x0001; //ignored
+const jint PURGE_TXCLEAR = 0x0004;
+
+/* OK */
+/*
+ * PurgeComm
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_purgePort
+ (JNIEnv *env, jobject object, jint portHandle, jint flags){
+ int clearValue = -1;
+ if((flags & PURGE_RXCLEAR) && (flags & PURGE_TXCLEAR)){
+ clearValue = TCIOFLUSH;
+ }
+ else if(flags & PURGE_RXCLEAR) {
+ clearValue = TCIFLUSH;
+ }
+ else if(flags & PURGE_TXCLEAR) {
+ clearValue = TCOFLUSH;
+ }
+ else if((flags & PURGE_RXABORT) || (flags & PURGE_TXABORT)){
+ return JNI_TRUE;
+ }
+ else {
+ return JNI_FALSE;
+ }
+ return tcflush(portHandle, clearValue) == 0 ? JNI_TRUE : JNI_FALSE;
+}
+
+/* OK */
+/* Closing the port */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_closePort
+ (JNIEnv *env, jobject object, jint portHandle){
+ return close(portHandle) == 0 ? JNI_TRUE : JNI_FALSE;
+}
+
+/* OK */
+/*
+ * Setting events mask
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setEventsMask
+ (JNIEnv *env, jobject object, jint portHandle, jint mask){
+ //Don't needed in linux, implemented in java code
+ return JNI_TRUE;
+}
+
+/* OK */
+/*
+ * Getting events mask
+ */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_getEventsMask
+ (JNIEnv *env, jobject object, jint portHandle){
+ //Don't needed in linux, implemented in java code
+ return -1;
+}
+
+/* OK */
+/*
+ * RTS line status changing (ON || OFF)
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setRTS
+ (JNIEnv *env, jobject object, jint portHandle, jboolean enabled){
+ int returnValue = 0;
+ int lineStatus;
+ ioctl(portHandle, TIOCMGET, &lineStatus);
+ if(enabled == JNI_TRUE){
+ lineStatus |= TIOCM_RTS;
+ }
+ else {
+ lineStatus &= ~TIOCM_RTS;
+ }
+ returnValue = ioctl(portHandle, TIOCMSET, &lineStatus);
+ return (returnValue >= 0 ? JNI_TRUE : JNI_FALSE);
+}
+
+/* OK */
+/*
+ * DTR line status changing (ON || OFF)
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setDTR
+ (JNIEnv *env, jobject object, jint portHandle, jboolean enabled){
+ int returnValue = 0;
+ int lineStatus;
+ ioctl(portHandle, TIOCMGET, &lineStatus);
+ if(enabled == JNI_TRUE){
+ lineStatus |= TIOCM_DTR;
+ }
+ else {
+ lineStatus &= ~TIOCM_DTR;
+ }
+ returnValue = ioctl(portHandle, TIOCMSET, &lineStatus);
+ return (returnValue >= 0 ? JNI_TRUE : JNI_FALSE);
+}
+
+/* OK */
+/*
+ * Writing data to the port
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_writeBytes
+ (JNIEnv *env, jobject object, jint portHandle, jbyteArray buffer){
+ jbyte* jBuffer = env->GetByteArrayElements(buffer, JNI_FALSE);
+ jint bufferSize = env->GetArrayLength(buffer);
+ jint result = write(portHandle, jBuffer, (size_t)bufferSize);
+ env->ReleaseByteArrayElements(buffer, jBuffer, 0);
+ return result == bufferSize ? JNI_TRUE : JNI_FALSE;
+}
+
+/* OK */
+/*
+ * Reading data from the port
+ */
+JNIEXPORT jbyteArray JNICALL Java_jssc_SerialNativeInterface_readBytes
+ (JNIEnv *env, jobject object, jint portHandle, jint byteCount){
+#ifdef __SunOS
+ jbyte *lpBuffer = new jbyte[byteCount];//Need for CC compiler
+ read(portHandle, lpBuffer, byteCount);
+#else
+ jbyte lpBuffer[byteCount];
+ read(portHandle, &lpBuffer, byteCount);
+#endif
+ jbyteArray returnArray = env->NewByteArray(byteCount);
+ env->SetByteArrayRegion(returnArray, 0, byteCount, lpBuffer);
+#ifdef __SunOS
+ delete(lpBuffer);
+#endif
+ return returnArray;
+}
+
+/* OK */
+/*
+ * Get bytes count in serial port buffers (Input and Output)
+ */
+JNIEXPORT jintArray JNICALL Java_jssc_SerialNativeInterface_getBuffersBytesCount
+ (JNIEnv *env, jobject object, jint portHandle){
+ jint returnValues[2];
+ returnValues[0] = -1; //Input buffer
+ returnValues[1] = -1; //Output buffer
+ jintArray returnArray = env->NewIntArray(2);
+ ioctl(portHandle, FIONREAD, &returnValues[0]);
+ ioctl(portHandle, TIOCOUTQ, &returnValues[1]);
+ env->SetIntArrayRegion(returnArray, 0, 2, returnValues);
+ return returnArray;
+}
+
+const jint FLOWCONTROL_NONE = 0;
+const jint FLOWCONTROL_RTSCTS_IN = 1;
+const jint FLOWCONTROL_RTSCTS_OUT = 2;
+const jint FLOWCONTROL_XONXOFF_IN = 4;
+const jint FLOWCONTROL_XONXOFF_OUT = 8;
+
+/* OK */
+/*
+ * Setting flow control mode
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setFlowControlMode
+ (JNIEnv *env, jobject object, jint portHandle, jint mask){
+ jboolean returnValue = JNI_FALSE;
+ termios *settings = new termios();
+ if(tcgetattr(portHandle, settings) == 0){
+ settings->c_cflag &= ~CRTSCTS;
+ settings->c_iflag &= ~(IXON | IXOFF);
+ if(mask != FLOWCONTROL_NONE){
+ if(((mask & FLOWCONTROL_RTSCTS_IN) == FLOWCONTROL_RTSCTS_IN) || ((mask & FLOWCONTROL_RTSCTS_OUT) == FLOWCONTROL_RTSCTS_OUT)){
+ settings->c_cflag |= CRTSCTS;
+ }
+ if((mask & FLOWCONTROL_XONXOFF_IN) == FLOWCONTROL_XONXOFF_IN){
+ settings->c_iflag |= IXOFF;
+ }
+ if((mask & FLOWCONTROL_XONXOFF_OUT) == FLOWCONTROL_XONXOFF_OUT){
+ settings->c_iflag |= IXON;
+ }
+ }
+ if(tcsetattr(portHandle, TCSANOW, settings) == 0){
+ returnValue = JNI_TRUE;
+ }
+ }
+ delete settings;
+ return returnValue;
+}
+
+/* OK */
+/*
+ * Getting flow control mode
+ */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_getFlowControlMode
+ (JNIEnv *env, jobject object, jint portHandle){
+ jint returnValue = 0;
+ termios *settings = new termios();
+ if(tcgetattr(portHandle, settings) == 0){
+ if(settings->c_cflag & CRTSCTS){
+ returnValue |= (FLOWCONTROL_RTSCTS_IN | FLOWCONTROL_RTSCTS_OUT);
+ }
+ if(settings->c_iflag & IXOFF){
+ returnValue |= FLOWCONTROL_XONXOFF_IN;
+ }
+ if(settings->c_iflag & IXON){
+ returnValue |= FLOWCONTROL_XONXOFF_OUT;
+ }
+ }
+ return returnValue;
+}
+
+/* OK */
+/*
+ * Send break for setted duration
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_sendBreak
+ (JNIEnv *env, jobject object, jint portHandle, jint duration){
+ jboolean returnValue = JNI_FALSE;
+ if(duration > 0){
+ if(ioctl(portHandle, TIOCSBRK, 0) >= 0){
+ int sec = (duration >= 1000 ? duration/1000 : 0);
+ int nanoSec = (sec > 0 ? duration - sec*1000 : duration)*1000000;
+ struct timespec *timeStruct = new timespec();
+ timeStruct->tv_sec = sec;
+ timeStruct->tv_nsec = nanoSec;
+ nanosleep(timeStruct, NULL);
+ delete(timeStruct);
+ if(ioctl(portHandle, TIOCCBRK, 0) >= 0){
+ returnValue = JNI_TRUE;
+ }
+ }
+ }
+ return returnValue;
+}
+
+/* OK */
+/*
+ * Return "statusLines" from ioctl(portHandle, TIOCMGET, &statusLines)
+ * Need for "_waitEvents" and "_getLinesStatus"
+ */
+int getLinesStatus(jint portHandle) {
+ int statusLines;
+ ioctl(portHandle, TIOCMGET, &statusLines);
+ return statusLines;
+}
+
+/* OK */
+/*
+ * Not supported in Solaris and Mac OS X
+ *
+ * Get interrupts count for:
+ * 0 - Break(for BREAK event)
+ * 1 - TX(for TXEMPTY event)
+ * --ERRORS(for ERR event)--
+ * 2 - Frame
+ * 3 - Overrun
+ * 4 - Parity
+ */
+void getInterruptsCount(jint portHandle, int intArray[]) {
+#ifdef TIOCGICOUNT
+ struct serial_icounter_struct *icount = new serial_icounter_struct();
+ if(ioctl(portHandle, TIOCGICOUNT, icount) >= 0){
+ intArray[0] = icount->brk;
+ intArray[1] = icount->tx;
+ intArray[2] = icount->frame;
+ intArray[3] = icount->overrun;
+ intArray[4] = icount->parity;
+ }
+ delete icount;
+#endif
+}
+
+const jint INTERRUPT_BREAK = 512;
+const jint INTERRUPT_TX = 1024;
+const jint INTERRUPT_FRAME = 2048;
+const jint INTERRUPT_OVERRUN = 4096;
+const jint INTERRUPT_PARITY = 8192;
+
+const jint EV_CTS = 8;
+const jint EV_DSR = 16;
+const jint EV_RING = 256;
+const jint EV_RLSD = 32;
+const jint EV_RXCHAR = 1;
+//const jint EV_RXFLAG = 2; //Not supported
+const jint EV_TXEMPTY = 4;
+const jint events[] = {INTERRUPT_BREAK,
+ INTERRUPT_TX,
+ INTERRUPT_FRAME,
+ INTERRUPT_OVERRUN,
+ INTERRUPT_PARITY,
+ EV_CTS,
+ EV_DSR,
+ EV_RING,
+ EV_RLSD,
+ EV_RXCHAR,
+ //EV_RXFLAG, //Not supported
+ EV_TXEMPTY};
+
+/* OK */
+/*
+ * Collecting data for EventListener class (Linux have no implementation of "WaitCommEvent" function from Windows)
+ *
+ */
+JNIEXPORT jobjectArray JNICALL Java_jssc_SerialNativeInterface_waitEvents
+ (JNIEnv *env, jobject object, jint portHandle) {
+
+ jclass intClass = env->FindClass("[I");
+ jobjectArray returnArray = env->NewObjectArray(sizeof(events)/sizeof(jint), intClass, NULL);
+
+ /*Input buffer*/
+ jint bytesCountIn = 0;
+ ioctl(portHandle, FIONREAD, &bytesCountIn);
+
+ /*Output buffer*/
+ jint bytesCountOut = 0;
+ ioctl(portHandle, TIOCOUTQ, &bytesCountOut);
+
+ /*Lines status*/
+ int statusLines = getLinesStatus(portHandle);
+
+ jint statusCTS = 0;
+ jint statusDSR = 0;
+ jint statusRING = 0;
+ jint statusRLSD = 0;
+
+ /*CTS status*/
+ if(statusLines & TIOCM_CTS){
+ statusCTS = 1;
+ }
+
+ /*DSR status*/
+ if(statusLines & TIOCM_DSR){
+ statusDSR = 1;
+ }
+
+ /*RING status*/
+ if(statusLines & TIOCM_RNG){
+ statusRING = 1;
+ }
+
+ /*RLSD(DCD) status*/
+ if(statusLines & TIOCM_CAR){
+ statusRLSD = 1;
+ }
+
+ /*Interrupts*/
+ int interrupts[] = {-1, -1, -1, -1, -1};
+ getInterruptsCount(portHandle, interrupts);
+
+ jint interruptBreak = interrupts[0];
+ jint interruptTX = interrupts[1];
+ jint interruptFrame = interrupts[2];
+ jint interruptOverrun = interrupts[3];
+ jint interruptParity = interrupts[4];
+
+ for(int i = 0; i < sizeof(events)/sizeof(jint); i++){
+ jint returnValues[2];
+ switch(events[i]) {
+
+ case INTERRUPT_BREAK: //Interrupt Break - for BREAK event
+ returnValues[1] = interruptBreak;
+ goto forEnd;
+ case INTERRUPT_TX: //Interrupt TX - for TXEMPTY event
+ returnValues[1] = interruptTX;
+ goto forEnd;
+ case INTERRUPT_FRAME: //Interrupt Frame - for ERR event
+ returnValues[1] = interruptFrame;
+ goto forEnd;
+ case INTERRUPT_OVERRUN: //Interrupt Overrun - for ERR event
+ returnValues[1] = interruptOverrun;
+ goto forEnd;
+ case INTERRUPT_PARITY: //Interrupt Parity - for ERR event
+ returnValues[1] = interruptParity;
+ goto forEnd;
+ case EV_CTS:
+ returnValues[1] = statusCTS;
+ goto forEnd;
+ case EV_DSR:
+ returnValues[1] = statusDSR;
+ goto forEnd;
+ case EV_RING:
+ returnValues[1] = statusRING;
+ goto forEnd;
+ case EV_RLSD: /*DCD*/
+ returnValues[1] = statusRLSD;
+ goto forEnd;
+ case EV_RXCHAR:
+ returnValues[1] = bytesCountIn;
+ goto forEnd;
+ /*case EV_RXFLAG: // Event RXFLAG - Not supported
+ returnValues[0] = EV_RXFLAG;
+ returnValues[1] = 0;
+ goto forEnd;*/
+ case EV_TXEMPTY:
+ returnValues[1] = bytesCountOut;
+ goto forEnd;
+ }
+ forEnd: {
+ returnValues[0] = events[i];
+ jintArray singleResultArray = env->NewIntArray(2);
+ env->SetIntArrayRegion(singleResultArray, 0, 2, returnValues);
+ env->SetObjectArrayElement(returnArray, i, singleResultArray);
+ };
+ }
+ return returnArray;
+}
+
+/* OK */
+/*
+ * Getting serial ports names like an a String array (String[])
+ */
+JNIEXPORT jobjectArray JNICALL Java_jssc_SerialNativeInterface_getSerialPortNames
+ (JNIEnv *env, jobject object){
+ //Don't needed in linux, implemented in java code (Note: null will be returned)
+ return NULL;
+}
+
+/* OK */
+/*
+ * Getting lines status
+ *
+ * returnValues[0] - CTS
+ * returnValues[1] - DSR
+ * returnValues[2] - RING
+ * returnValues[3] - RLSD(DCD)
+ */
+JNIEXPORT jintArray JNICALL Java_jssc_SerialNativeInterface_getLinesStatus
+ (JNIEnv *env, jobject object, jint portHandle){
+ jint returnValues[4];
+ for(jint i = 0; i < 4; i++){
+ returnValues[i] = 0;
+ }
+ jintArray returnArray = env->NewIntArray(4);
+
+ /*Lines status*/
+ int statusLines = getLinesStatus(portHandle);
+
+ /*CTS status*/
+ if(statusLines & TIOCM_CTS){
+ returnValues[0] = 1;
+ }
+
+ /*DSR status*/
+ if(statusLines & TIOCM_DSR){
+ returnValues[1] = 1;
+ }
+
+ /*RING status*/
+ if(statusLines & TIOCM_RNG){
+ returnValues[2] = 1;
+ }
+
+ /*RLSD(DCD) status*/
+ if(statusLines & TIOCM_CAR){
+ returnValues[3] = 1;
+ }
+
+ env->SetIntArrayRegion(returnArray, 0, 4, returnValues);
+ return returnArray;
+}
diff --git a/src/cpp/jssc_SerialNativeInterface.h b/src/cpp/jssc_SerialNativeInterface.h
new file mode 100644
index 0000000..259da67
--- /dev/null
+++ b/src/cpp/jssc_SerialNativeInterface.h
@@ -0,0 +1,181 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+/* DO NOT EDIT THIS FILE - it is machine generated */
+#include
+/* Header for class jssc_SerialNativeInterface */
+
+#ifndef _Included_jssc_SerialNativeInterface
+#define _Included_jssc_SerialNativeInterface
+#ifdef __cplusplus
+extern "C" {
+#endif
+#undef jssc_SerialNativeInterface_OS_LINUX
+#define jssc_SerialNativeInterface_OS_LINUX 0L
+#undef jssc_SerialNativeInterface_OS_WINDOWS
+#define jssc_SerialNativeInterface_OS_WINDOWS 1L
+#undef jssc_SerialNativeInterface_OS_SOLARIS
+#define jssc_SerialNativeInterface_OS_SOLARIS 2L
+#undef jssc_SerialNativeInterface_OS_MAC_OS_X
+#define jssc_SerialNativeInterface_OS_MAC_OS_X 3L
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: openPort
+ * Signature: (Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_openPort
+ (JNIEnv *, jobject, jstring);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: setParams
+ * Signature: (IIIIIZZ)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setParams
+ (JNIEnv *, jobject, jint, jint, jint, jint, jint, jboolean, jboolean);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: purgePort
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_purgePort
+ (JNIEnv *, jobject, jint, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: closePort
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_closePort
+ (JNIEnv *, jobject, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: setEventsMask
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setEventsMask
+ (JNIEnv *, jobject, jint, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: getEventsMask
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_getEventsMask
+ (JNIEnv *, jobject, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: waitEvents
+ * Signature: (I)[[I
+ */
+JNIEXPORT jobjectArray JNICALL Java_jssc_SerialNativeInterface_waitEvents
+ (JNIEnv *, jobject, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: setRTS
+ * Signature: (IZ)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setRTS
+ (JNIEnv *, jobject, jint, jboolean);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: setDTR
+ * Signature: (IZ)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setDTR
+ (JNIEnv *, jobject, jint, jboolean);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: readBytes
+ * Signature: (II)[B
+ */
+JNIEXPORT jbyteArray JNICALL Java_jssc_SerialNativeInterface_readBytes
+ (JNIEnv *, jobject, jint, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: writeBytes
+ * Signature: (I[B)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_writeBytes
+ (JNIEnv *, jobject, jint, jbyteArray);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: getBuffersBytesCount
+ * Signature: (I)[I
+ */
+JNIEXPORT jintArray JNICALL Java_jssc_SerialNativeInterface_getBuffersBytesCount
+ (JNIEnv *, jobject, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: setFlowControlMode
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setFlowControlMode
+ (JNIEnv *, jobject, jint, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: getFlowControlMode
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_getFlowControlMode
+ (JNIEnv *, jobject, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: getSerialPortNames
+ * Signature: ()[Ljava/lang/String;
+ */
+JNIEXPORT jobjectArray JNICALL Java_jssc_SerialNativeInterface_getSerialPortNames
+ (JNIEnv *, jobject);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: getLinesStatus
+ * Signature: (I)[I
+ */
+JNIEXPORT jintArray JNICALL Java_jssc_SerialNativeInterface_getLinesStatus
+ (JNIEnv *, jobject, jint);
+
+/*
+ * Class: jssc_SerialNativeInterface
+ * Method: sendBreak
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_sendBreak
+ (JNIEnv *, jobject, jint, jint);
+
+#ifdef __cplusplus
+}
+#endif
+#endif
diff --git a/src/cpp/windows/jssc.c++ b/src/cpp/windows/jssc.c++
new file mode 100644
index 0000000..ba1c2cf
--- /dev/null
+++ b/src/cpp/windows/jssc.c++
@@ -0,0 +1,658 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+#include
+#include
+#include
+#include "jssc_SerialNativeInterface.h"
+
+/*
+ * Port opening.
+ */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_openPort(JNIEnv *env, jobject object, jstring portName){
+ char prefix[] = "\\\\.\\";
+ const char* port = env->GetStringUTFChars(portName, JNI_FALSE);
+ strcat(prefix, port);
+ HANDLE hComm;
+ hComm = CreateFile(prefix,
+ GENERIC_READ | GENERIC_WRITE,
+ 0,
+ 0,
+ OPEN_EXISTING,
+ FILE_FLAG_OVERLAPPED,
+ 0);
+ env->ReleaseStringUTFChars(portName, port);
+ //since 0.9 ->
+ if(hComm == INVALID_HANDLE_VALUE){
+ DWORD errorValue = GetLastError();
+ if(errorValue == ERROR_ACCESS_DENIED){
+ hComm = (HANDLE)-1;//Port busy
+ }
+ else if(errorValue == ERROR_FILE_NOT_FOUND){
+ hComm = (HANDLE)-2;//Port not found
+ }
+ }
+ //<- since 0.9
+#if defined(_X86_)
+ return (jint)hComm;
+#elif defined(__x86_64)
+ return (intptr_t)hComm;
+#endif
+};
+
+/*
+ * Setting serial port params.
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setParams
+ (JNIEnv *env, jobject object, jint portHandle, jint baudRate, jint byteSize, jint stopBits, jint parity, jboolean setRTS, jboolean setDTR){
+ HANDLE hComm = (HANDLE)portHandle;
+ DCB *dcb = new DCB();
+ jboolean returnValue = JNI_FALSE;
+ if(GetCommState(hComm, dcb)){
+ dcb->BaudRate = baudRate;
+ dcb->ByteSize = byteSize;
+ dcb->StopBits = stopBits;
+ dcb->Parity = parity;
+
+ //since 0.8 ->
+ if(setRTS == JNI_TRUE){
+ dcb->fRtsControl = RTS_CONTROL_ENABLE;
+ }
+ else {
+ dcb->fRtsControl = RTS_CONTROL_DISABLE;
+ }
+ if(setDTR == JNI_TRUE){
+ dcb->fDtrControl = DTR_CONTROL_ENABLE;
+ }
+ else {
+ dcb->fDtrControl = DTR_CONTROL_DISABLE;
+ }
+ dcb->fOutxCtsFlow = FALSE;
+ dcb->fOutxDsrFlow = FALSE;
+ dcb->fDsrSensitivity = FALSE;
+ dcb->fTXContinueOnXoff = TRUE;
+ dcb->fOutX = FALSE;
+ dcb->fInX = FALSE;
+ dcb->fErrorChar = FALSE;
+ dcb->fNull = FALSE;
+ dcb->fAbortOnError = FALSE;
+ dcb->XonLim = 2048;
+ dcb->XoffLim = 512;
+ dcb->XonChar = (char)17; //DC1
+ dcb->XoffChar = (char)19; //DC3
+ //<- since 0.8
+
+ if(SetCommState(hComm, dcb)){
+ returnValue = JNI_TRUE;
+ }
+ }
+ delete dcb;
+ return returnValue;
+}
+
+/*
+ * PurgeComm
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_purgePort
+ (JNIEnv *env, jobject object, jint portHandle, jint flags){
+ HANDLE hComm = (HANDLE)portHandle;
+ DWORD dwFlags = (DWORD)flags;
+ return (PurgeComm(hComm, dwFlags) ? JNI_TRUE : JNI_FALSE);
+}
+
+/*
+ * Port closing
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_closePort
+ (JNIEnv *env, jobject object, jint portHandle){
+ HANDLE hComm = (HANDLE)portHandle;
+ return (CloseHandle(hComm) ? JNI_TRUE : JNI_FALSE);
+}
+
+/*
+ * Set events mask
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setEventsMask
+ (JNIEnv *env, jobject object, jint portHandle, jint mask){
+ HANDLE hComm = (HANDLE)portHandle;
+ DWORD dwEvtMask = (DWORD)mask;
+ return (SetCommMask(hComm, dwEvtMask) ? JNI_TRUE : JNI_FALSE);
+}
+
+/*
+ * Get events mask
+ */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_getEventsMask
+ (JNIEnv *env, jobject object, jint portHandle){
+ HANDLE hComm = (HANDLE)portHandle;
+ DWORD lpEvtMask;
+ if(GetCommMask(hComm, &lpEvtMask)){
+ return (jint)lpEvtMask;
+ }
+ else {
+ return -1;
+ }
+}
+
+/*
+ * Change RTS line state (ON || OFF)
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setRTS
+ (JNIEnv *env, jobject object, jint portHandle, jboolean enabled){
+ HANDLE hComm = (HANDLE)portHandle;
+ if(enabled == JNI_TRUE){
+ return (EscapeCommFunction(hComm, SETRTS) ? JNI_TRUE : JNI_FALSE);
+ }
+ else {
+ return (EscapeCommFunction(hComm, CLRRTS) ? JNI_TRUE : JNI_FALSE);
+ }
+}
+
+/*
+ * Change DTR line state (ON || OFF)
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setDTR
+ (JNIEnv *env, jobject object, jint portHandle, jboolean enabled){
+ HANDLE hComm = (HANDLE)portHandle;
+ if(enabled == JNI_TRUE){
+ return (EscapeCommFunction(hComm, SETDTR) ? JNI_TRUE : JNI_FALSE);
+ }
+ else {
+ return (EscapeCommFunction(hComm, CLRDTR) ? JNI_TRUE : JNI_FALSE);
+ }
+}
+
+/*
+ * Write data to port
+ * portHandle - port handle
+ * buffer - byte array for sending
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_writeBytes
+ (JNIEnv *env, jobject object, jint portHandle, jbyteArray buffer){
+ HANDLE hComm = (HANDLE)portHandle;
+ DWORD lpNumberOfBytesTransferred;
+ DWORD lpNumberOfBytesWritten;
+ OVERLAPPED *overlapped = new OVERLAPPED();
+ jboolean returnValue = JNI_FALSE;
+ jbyte* jBuffer = env->GetByteArrayElements(buffer, JNI_FALSE);
+ overlapped->hEvent = CreateEventA(NULL, true, false, NULL);
+ if(WriteFile(hComm, jBuffer, (DWORD)env->GetArrayLength(buffer), &lpNumberOfBytesWritten, overlapped)){
+ returnValue = JNI_TRUE;
+ }
+ else if(GetLastError() == ERROR_IO_PENDING){
+ if(WaitForSingleObject(overlapped->hEvent, INFINITE) == WAIT_OBJECT_0){
+ if(GetOverlappedResult(hComm, overlapped, &lpNumberOfBytesTransferred, false)){
+ returnValue = JNI_TRUE;
+ }
+ }
+ }
+ env->ReleaseByteArrayElements(buffer, jBuffer, 0);
+ CloseHandle(overlapped->hEvent);
+ delete overlapped;
+ return returnValue;
+}
+
+/*
+ * Read data from port
+ * portHandle - port handle
+ * byteCount - count of bytes for reading
+ */
+JNIEXPORT jbyteArray JNICALL Java_jssc_SerialNativeInterface_readBytes
+ (JNIEnv *env, jobject object, jint portHandle, jint byteCount){
+ HANDLE hComm = (HANDLE)portHandle;
+ DWORD lpNumberOfBytesTransferred;
+ DWORD lpNumberOfBytesRead;
+ OVERLAPPED *overlapped = new OVERLAPPED();
+ jbyte lpBuffer[byteCount];
+ jbyteArray returnArray = env->NewByteArray(byteCount);
+ overlapped->hEvent = CreateEventA(NULL, true, false, NULL);
+ if(ReadFile(hComm, lpBuffer, (DWORD)byteCount, &lpNumberOfBytesRead, overlapped)){
+ env->SetByteArrayRegion(returnArray, 0, byteCount, lpBuffer);
+ }
+ else if(GetLastError() == ERROR_IO_PENDING){
+ if(WaitForSingleObject(overlapped->hEvent, INFINITE) == WAIT_OBJECT_0){
+ if(GetOverlappedResult(hComm, overlapped, &lpNumberOfBytesTransferred, false)){
+ env->SetByteArrayRegion(returnArray, 0, byteCount, lpBuffer);
+ }
+ }
+ }
+ CloseHandle(overlapped->hEvent);
+ delete overlapped;
+ return returnArray;
+}
+
+/*
+ * Get bytes count in serial port buffers (Input and Output)
+ */
+JNIEXPORT jintArray JNICALL Java_jssc_SerialNativeInterface_getBuffersBytesCount
+ (JNIEnv *env, jobject object, jint portHandle){
+ HANDLE hComm = (HANDLE)portHandle;
+ jint returnValues[2];
+ returnValues[0] = -1;
+ returnValues[1] = -1;
+ jintArray returnArray = env->NewIntArray(2);
+ DWORD lpErrors;
+ COMSTAT *comstat = new COMSTAT();
+ if(ClearCommError(hComm, &lpErrors, comstat)){
+ returnValues[0] = (jint)comstat->cbInQue;
+ returnValues[1] = (jint)comstat->cbOutQue;
+ }
+ else {
+ returnValues[0] = -1;
+ returnValues[1] = -1;
+ }
+ delete comstat;
+ env->SetIntArrayRegion(returnArray, 0, 2, returnValues);
+ return returnArray;
+}
+
+//since 0.8 ->
+const jint FLOWCONTROL_NONE = 0;
+const jint FLOWCONTROL_RTSCTS_IN = 1;
+const jint FLOWCONTROL_RTSCTS_OUT = 2;
+const jint FLOWCONTROL_XONXOFF_IN = 4;
+const jint FLOWCONTROL_XONXOFF_OUT = 8;
+//<- since 0.8
+
+/*
+ * Setting flow control mode
+ *
+ * since 0.8
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_setFlowControlMode
+ (JNIEnv *env, jobject object, jint portHandle, jint mask){
+ HANDLE hComm = (HANDLE)portHandle;
+ jboolean returnValue = JNI_FALSE;
+ DCB *dcb = new DCB();
+ if(GetCommState(hComm, dcb)){
+ dcb->fRtsControl = RTS_CONTROL_ENABLE;
+ dcb->fOutxCtsFlow = FALSE;
+ dcb->fOutX = FALSE;
+ dcb->fInX = FALSE;
+ if(mask != FLOWCONTROL_NONE){
+ if((mask & FLOWCONTROL_RTSCTS_IN) == FLOWCONTROL_RTSCTS_IN){
+ dcb->fRtsControl = RTS_CONTROL_HANDSHAKE;
+ }
+ if((mask & FLOWCONTROL_RTSCTS_OUT) == FLOWCONTROL_RTSCTS_OUT){
+ dcb->fOutxCtsFlow = TRUE;
+ }
+ if((mask & FLOWCONTROL_XONXOFF_IN) == FLOWCONTROL_XONXOFF_IN){
+ dcb->fInX = TRUE;
+ }
+ if((mask & FLOWCONTROL_XONXOFF_OUT) == FLOWCONTROL_XONXOFF_OUT){
+ dcb->fOutX = TRUE;
+ }
+ }
+ if(SetCommState(hComm, dcb)){
+ returnValue = JNI_TRUE;
+ }
+ }
+ delete dcb;
+ return returnValue;
+}
+
+/*
+ * Getting flow control mode
+ *
+ * since 0.8
+ */
+JNIEXPORT jint JNICALL Java_jssc_SerialNativeInterface_getFlowControlMode
+ (JNIEnv *env, jobject object, jint portHandle){
+ HANDLE hComm = (HANDLE)portHandle;
+ jint returnValue = 0;
+ DCB *dcb = new DCB();
+ if(GetCommState(hComm, dcb)){
+ if(dcb->fRtsControl == RTS_CONTROL_HANDSHAKE){
+ returnValue |= FLOWCONTROL_RTSCTS_IN;
+ }
+ if(dcb->fOutxCtsFlow == TRUE){
+ returnValue |= FLOWCONTROL_RTSCTS_OUT;
+ }
+ if(dcb->fInX == TRUE){
+ returnValue |= FLOWCONTROL_XONXOFF_IN;
+ }
+ if(dcb->fOutX == TRUE){
+ returnValue |= FLOWCONTROL_XONXOFF_OUT;
+ }
+ }
+ delete dcb;
+ return returnValue;
+}
+
+/*
+ * Send break for setted duration
+ *
+ * since 0.8
+ */
+JNIEXPORT jboolean JNICALL Java_jssc_SerialNativeInterface_sendBreak
+ (JNIEnv *env, jobject object, jint portHandle, jint duration){
+ HANDLE hComm = (HANDLE)portHandle;
+ jboolean returnValue = JNI_FALSE;
+ if(duration > 0){
+ if(SetCommBreak(hComm) > 0){
+ Sleep(duration);
+ if(ClearCommBreak(hComm) > 0){
+ returnValue = JNI_TRUE;
+ }
+ }
+ }
+ return returnValue;
+}
+
+/*
+ * Wait event
+ * portHandle - port handle
+ */
+JNIEXPORT jobjectArray JNICALL Java_jssc_SerialNativeInterface_waitEvents
+ (JNIEnv *env, jobject object, jint portHandle) {
+ HANDLE hComm = (HANDLE)portHandle;
+ DWORD lpEvtMask = 0;
+ DWORD lpNumberOfBytesTransferred = 0;
+ OVERLAPPED *overlapped = new OVERLAPPED();
+ jclass intClass = env->FindClass("[I");
+ jobjectArray returnArray;
+ boolean functionSuccessful = false;
+ overlapped->hEvent = CreateEventA(NULL, true, false, NULL);
+ if(WaitCommEvent(hComm, &lpEvtMask, overlapped)){
+ functionSuccessful = true;
+ }
+ else if(GetLastError() == ERROR_IO_PENDING){
+ if(WaitForSingleObject(overlapped->hEvent, INFINITE) == WAIT_OBJECT_0){
+ if(GetOverlappedResult(hComm, overlapped, &lpNumberOfBytesTransferred, false)){
+ functionSuccessful = true;
+ }
+ }
+ }
+ if(functionSuccessful){
+ boolean executeGetCommModemStatus = false;
+ boolean executeClearCommError = false;
+ DWORD events[9];//fixed since 0.8 (old value is 8)
+ jint eventsCount = 0;
+ if((EV_BREAK & lpEvtMask) == EV_BREAK){
+ events[eventsCount] = EV_BREAK;
+ eventsCount++;
+ }
+ if((EV_CTS & lpEvtMask) == EV_CTS){
+ events[eventsCount] = EV_CTS;
+ eventsCount++;
+ executeGetCommModemStatus = true;
+ }
+ if((EV_DSR & lpEvtMask) == EV_DSR){
+ events[eventsCount] = EV_DSR;
+ eventsCount++;
+ executeGetCommModemStatus = true;
+ }
+ if((EV_ERR & lpEvtMask) == EV_ERR){
+ events[eventsCount] = EV_ERR;
+ eventsCount++;
+ executeClearCommError = true;
+ }
+ if((EV_RING & lpEvtMask) == EV_RING){
+ events[eventsCount] = EV_RING;
+ eventsCount++;
+ executeGetCommModemStatus = true;
+ }
+ if((EV_RLSD & lpEvtMask) == EV_RLSD){
+ events[eventsCount] = EV_RLSD;
+ eventsCount++;
+ executeGetCommModemStatus = true;
+ }
+ if((EV_RXCHAR & lpEvtMask) == EV_RXCHAR){
+ events[eventsCount] = EV_RXCHAR;
+ eventsCount++;
+ executeClearCommError = true;
+ }
+ if((EV_RXFLAG & lpEvtMask) == EV_RXFLAG){
+ events[eventsCount] = EV_RXFLAG;
+ eventsCount++;
+ executeClearCommError = true;
+ }
+ if((EV_TXEMPTY & lpEvtMask) == EV_TXEMPTY){
+ events[eventsCount] = EV_TXEMPTY;
+ eventsCount++;
+ executeClearCommError = true;
+ }
+ /*
+ * Execute GetCommModemStatus function if it's needed (get lines status)
+ */
+ jint statusCTS = 0;
+ jint statusDSR = 0;
+ jint statusRING = 0;
+ jint statusRLSD = 0;
+ boolean successGetCommModemStatus = false;
+ if(executeGetCommModemStatus){
+ DWORD lpModemStat;
+ if(GetCommModemStatus(hComm, &lpModemStat)){
+ successGetCommModemStatus = true;
+ if((MS_CTS_ON & lpModemStat) == MS_CTS_ON){
+ statusCTS = 1;
+ }
+ if((MS_DSR_ON & lpModemStat) == MS_DSR_ON){
+ statusDSR = 1;
+ }
+ if((MS_RING_ON & lpModemStat) == MS_RING_ON){
+ statusRING = 1;
+ }
+ if((MS_RLSD_ON & lpModemStat) == MS_RLSD_ON){
+ statusRLSD = 1;
+ }
+ }
+ else {
+ jint lastError = (jint)GetLastError();
+ statusCTS = lastError;
+ statusDSR = lastError;
+ statusRING = lastError;
+ statusRLSD = lastError;
+ }
+ }
+ /*
+ * Execute ClearCommError function if it's needed (get count of bytes in buffers and errors)
+ */
+ jint bytesCountIn = 0;
+ jint bytesCountOut = 0;
+ jint communicationsErrors = 0;
+ boolean successClearCommError = false;
+ if(executeClearCommError){
+ DWORD lpErrors;
+ COMSTAT *comstat = new COMSTAT();
+ if(ClearCommError(hComm, &lpErrors, comstat)){
+ successClearCommError = true;
+ bytesCountIn = (jint)comstat->cbInQue;
+ bytesCountOut = (jint)comstat->cbOutQue;
+ communicationsErrors = (jint)lpErrors;
+ }
+ else {
+ jint lastError = (jint)GetLastError();
+ bytesCountIn = lastError;
+ bytesCountOut = lastError;
+ communicationsErrors = lastError;
+ }
+ delete comstat;
+ }
+ /*
+ * Create int[][] for events values
+ */
+ returnArray = env->NewObjectArray(eventsCount, intClass, NULL);
+ /*
+ * Set events values
+ */
+ for(jint i = 0; i < eventsCount; i++){
+ jint returnValues[2];
+ switch(events[i]){
+ case EV_BREAK:
+ returnValues[0] = (jint)events[i];
+ returnValues[1] = 0;
+ goto forEnd;
+ case EV_CTS:
+ returnValues[1] = statusCTS;
+ goto modemStatus;
+ case EV_DSR:
+ returnValues[1] = statusDSR;
+ goto modemStatus;
+ case EV_ERR:
+ returnValues[1] = communicationsErrors;
+ goto bytesAndErrors;
+ case EV_RING:
+ returnValues[1] = statusRING;
+ goto modemStatus;
+ case EV_RLSD:
+ returnValues[1] = statusRLSD;
+ goto modemStatus;
+ case EV_RXCHAR:
+ returnValues[1] = bytesCountIn;
+ goto bytesAndErrors;
+ case EV_RXFLAG:
+ returnValues[1] = bytesCountIn;
+ goto bytesAndErrors;
+ case EV_TXEMPTY:
+ returnValues[1] = bytesCountOut;
+ goto bytesAndErrors;
+ default:
+ returnValues[0] = (jint)events[i];
+ returnValues[1] = 0;
+ goto forEnd;
+ };
+ modemStatus: {
+ if(successGetCommModemStatus){
+ returnValues[0] = (jint)events[i];
+ }
+ else {
+ returnValues[0] = -1;
+ }
+ goto forEnd;
+ }
+ bytesAndErrors: {
+ if(successClearCommError){
+ returnValues[0] = (jint)events[i];
+ }
+ else {
+ returnValues[0] = -1;
+ }
+ goto forEnd;
+ }
+ forEnd: {
+ jintArray singleResultArray = env->NewIntArray(2);
+ env->SetIntArrayRegion(singleResultArray, 0, 2, returnValues);
+ env->SetObjectArrayElement(returnArray, i, singleResultArray);
+ };
+ }
+ }
+ else {
+ returnArray = env->NewObjectArray(1, intClass, NULL);
+ jint returnValues[2];
+ returnValues[0] = -1;
+ returnValues[1] = (jint)GetLastError();
+ jintArray singleResultArray = env->NewIntArray(2);
+ env->SetIntArrayRegion(singleResultArray, 0, 2, returnValues);
+ env->SetObjectArrayElement(returnArray, 0, singleResultArray);
+ };
+ CloseHandle(overlapped->hEvent);
+ delete overlapped;
+ return returnArray;
+}
+
+/*
+ * Get serial port names
+ */
+JNIEXPORT jobjectArray JNICALL Java_jssc_SerialNativeInterface_getSerialPortNames
+ (JNIEnv *env, jobject object){
+ HKEY phkResult;
+ LPCSTR lpSubKey = "HARDWARE\\DEVICEMAP\\SERIALCOMM\\";
+ jobjectArray returnArray = NULL;
+ if(RegOpenKeyExA(HKEY_LOCAL_MACHINE, lpSubKey, 0, KEY_READ, &phkResult) == ERROR_SUCCESS){
+ boolean hasMoreElements = true;
+ DWORD keysCount = 0;
+ char valueName[256];
+ DWORD valueNameSize;
+ DWORD enumResult;
+ while(hasMoreElements){
+ valueNameSize = 256;
+ enumResult = RegEnumValueA(phkResult, keysCount, valueName, &valueNameSize, NULL, NULL, NULL, NULL);
+ if(enumResult == ERROR_SUCCESS){
+ keysCount++;
+ }
+ else if(enumResult == ERROR_NO_MORE_ITEMS){
+ hasMoreElements = false;
+ }
+ else {
+ hasMoreElements = false;
+ }
+ }
+ if(keysCount > 0){
+ jclass stringClass = env->FindClass("java/lang/String");
+ returnArray = env->NewObjectArray((jsize)keysCount, stringClass, NULL);
+ char lpValueName[256];
+ DWORD lpcchValueName;
+ byte lpData[256];
+ DWORD lpcbData;
+ DWORD result;
+ for(DWORD i = 0; i < keysCount; i++){
+ lpcchValueName = 256;
+ lpcbData = 256;
+ result = RegEnumValueA(phkResult, i, lpValueName, &lpcchValueName, NULL, NULL, lpData, &lpcbData);
+ if(result == ERROR_SUCCESS){
+ env->SetObjectArrayElement(returnArray, i, env->NewStringUTF((char*)lpData));
+ }
+ }
+ }
+ CloseHandle(phkResult);
+ }
+ return returnArray;
+}
+
+/*
+ * Get lines status
+ *
+ * returnValues[0] - CTS
+ * returnValues[1] - DSR
+ * returnValues[2] - RING
+ * returnValues[3] - RLSD
+ *
+ */
+JNIEXPORT jintArray JNICALL Java_jssc_SerialNativeInterface_getLinesStatus
+ (JNIEnv *env, jobject object, jint portHandle){
+ HANDLE hComm = (HANDLE)portHandle;
+ DWORD lpModemStat;
+ jint returnValues[4];
+ for(jint i = 0; i < 4; i++){
+ returnValues[i] = 0;
+ }
+ jintArray returnArray = env->NewIntArray(4);
+ if(GetCommModemStatus(hComm, &lpModemStat)){
+ if((MS_CTS_ON & lpModemStat) == MS_CTS_ON){
+ returnValues[0] = 1;
+ }
+ if((MS_DSR_ON & lpModemStat) == MS_DSR_ON){
+ returnValues[1] = 1;
+ }
+ if((MS_RING_ON & lpModemStat) == MS_RING_ON){
+ returnValues[2] = 1;
+ }
+ if((MS_RLSD_ON & lpModemStat) == MS_RLSD_ON){
+ returnValues[3] = 1;
+ }
+ }
+ env->SetIntArrayRegion(returnArray, 0, 4, returnValues);
+ return returnArray;
+}
diff --git a/src/java/jssc/SerialNativeInterface.java b/src/java/jssc/SerialNativeInterface.java
new file mode 100644
index 0000000..2dcfbce
--- /dev/null
+++ b/src/java/jssc/SerialNativeInterface.java
@@ -0,0 +1,403 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+package jssc;
+
+import java.io.File;
+import java.io.FileOutputStream;
+import java.io.InputStream;
+
+/**
+ *
+ * @author scream3r
+ */
+public class SerialNativeInterface {
+
+ private static final String libVersion = "0.9"; //jSSC-0.9.0 Release from 21.12.2011
+ private static final String libMinorSuffix = "0"; //since 0.9.0
+
+ public static final int OS_LINUX = 0;
+ public static final int OS_WINDOWS = 1;
+ public static final int OS_SOLARIS = 2;//since 0.9.0
+ public static final int OS_MAC_OS_X = 3;//since 0.9.0
+
+ private static int osType = -1;
+
+ static {
+ String libFolderPath;
+ String libName;
+
+ String osName = System.getProperty("os.name");
+ String architecture = System.getProperty("os.arch");
+ String userHome = System.getProperty("user.home");
+ String fileSeparator = System.getProperty("file.separator");
+
+ if(osName.equals("Linux")){
+ osName = "linux";
+ osType = OS_LINUX;
+ }
+ else if(osName.startsWith("Win")){
+ osName = "windows";
+ osType = OS_WINDOWS;
+ }//since 0.9.0 ->
+ else if(osName.equals("SunOS")){
+ osName = "solaris";
+ osType = OS_SOLARIS;
+ }
+ else if(osName.equals("Mac OS X")){
+ osName = "mac_os_x";
+ osType = OS_MAC_OS_X;
+ }//<- since 0.9.0
+
+ if(architecture.equals("i386") || architecture.equals("i686")){
+ architecture = "x86";
+ }
+ else if(architecture.equals("amd64")){
+ architecture = "x86_64";
+ }
+
+ libFolderPath = userHome + fileSeparator + ".jssc" + fileSeparator + osName;
+ libName = "jSSC-" + libVersion + "_" + architecture;
+ libName = System.mapLibraryName(libName);
+
+ boolean loadLib = false;
+
+ if(isLibFolderExist(libFolderPath)){
+ if(isLibFileExist(libFolderPath + fileSeparator + libName)){
+ loadLib = true;
+ }
+ else {
+ if(extractLib((libFolderPath + fileSeparator + libName), osName, libName)){
+ loadLib = true;
+ }
+ }
+ }
+ else {
+ if(new File(libFolderPath).mkdirs()){
+ if(extractLib((libFolderPath + fileSeparator + libName), osName, libName)){
+ loadLib = true;
+ }
+ }
+ }
+
+ if(loadLib){
+ System.load(libFolderPath + fileSeparator + libName);
+ }
+ }
+
+ /**
+ * Is library folder exists
+ *
+ * @param libFolderPath
+ *
+ * @since 0.8
+ */
+ private static boolean isLibFolderExist(String libFolderPath) {
+ boolean returnValue = false;
+ File folder = new File(libFolderPath);
+ if(folder.exists() && folder.isDirectory()){
+ returnValue = true;
+ }
+ return returnValue;
+ }
+
+ /**
+ * Is library file exists
+ *
+ * @param libFilePath
+ *
+ * @since 0.8
+ */
+ private static boolean isLibFileExist(String libFilePath) {
+ boolean returnValue = false;
+ File folder = new File(libFilePath);
+ if(folder.exists() && folder.isFile()){
+ returnValue = true;
+ }
+ return returnValue;
+ }
+
+ /**
+ * Extract lib to lib folder
+ *
+ * @param libFilePath
+ * @param osName
+ * @param libName
+ *
+ * @since 0.8
+ */
+ private static boolean extractLib(String libFilePath, String osName, String libName) {
+ boolean returnValue = false;
+ File libFile = new File(libFilePath);
+ InputStream input = null;
+ FileOutputStream output = null;
+ input = SerialNativeInterface.class.getResourceAsStream("/libs/" + osName + "/" + libName);
+ if(input != null){
+ int read;
+ byte[] buffer = new byte[4096];
+ try {
+ output = new FileOutputStream(libFilePath);
+ while((read = input.read(buffer)) != -1){
+ output.write(buffer, 0, read);
+ }
+ output.close();
+ input.close();
+ returnValue = true;
+ }
+ catch (Exception ex) {
+ try {
+ output.close();
+ if(libFile.exists()){
+ libFile.delete();
+ }
+ }
+ catch (Exception ex_out) {
+ //Do nothing
+ }
+ try {
+ input.close();
+ }
+ catch (Exception ex_in) {
+ //Do nothing
+ }
+ }
+ }
+ return returnValue;
+ }
+
+ /**
+ * Get OS type (OS_LINUX || OS_WINDOWS || OS_SOLARIS)
+ *
+ * @since 0.8
+ */
+ public static int getOsType() {
+ return osType;
+ }
+
+ /**
+ * Get jSSC version. The version of library is Base Version + Minor Suffix
+ *
+ * @since 0.8
+ */
+ public static String getLibraryVersion() {
+ return libVersion + "." + libMinorSuffix;
+ }
+
+ /**
+ * Get jSSC Base Version
+ *
+ * @since 0.9.0
+ */
+ public static String getLibraryBaseVersion() {
+ return libVersion;
+ }
+
+ /**
+ * Get jSSC minor suffix. For example in version 0.8.1 - 1 is a minor suffix
+ *
+ * @since 0.9.0
+ */
+ public static String getLibraryMinorSuffix() {
+ return libMinorSuffix;
+ }
+
+ /**
+ * Open port
+ *
+ * @param portName name of port for opening
+ *
+ * @return handle of opened port or -1 if opening of the port was unsuccessful
+ */
+ public native int openPort(String portName);
+
+ /**
+ * Setting the parameters of opened port
+ *
+ * @param handle handle of opened port
+ * @param baudRate data transfer rate
+ * @param dataBits number of data bits
+ * @param stopBits number of stop bits
+ * @param parity parity
+ * @param setRTS initial state of RTS line (ON/OFF)
+ * @param setDTR initial state of DTR line (ON/OFF)
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ */
+ public native boolean setParams(int handle, int baudRate, int dataBits, int stopBits, int parity, boolean setRTS, boolean setDTR);
+
+ /**
+ * Purge of input and output buffer
+ *
+ * @param handle handle of opened port
+ * @param flags flags specifying required actions for purgePort method
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ */
+ public native boolean purgePort(int handle, int flags);
+
+ /**
+ * Close port
+ *
+ * @param handle handle of opened port
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ */
+ public native boolean closePort(int handle);
+
+ /**
+ * Set events mask
+ *
+ * @param handle handle of opened port
+ * @param mask events mask
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ */
+ public native boolean setEventsMask(int handle, int mask);
+
+ /**
+ * Get events mask
+ *
+ * @param handle handle of opened port
+ *
+ * @return Method returns event mask as a variable of int type
+ */
+ public native int getEventsMask(int handle);
+
+ /**
+ * Wait events
+ *
+ * @param handle handle of opened port
+ *
+ * @return Method returns two-dimensional array containing event types and their values
+ * (events[i][0] - event type, events[i][1] - event value).
+ */
+ public native int[][] waitEvents(int handle);
+
+ /**
+ * Change RTS line state
+ *
+ * @param handle handle of opened port
+ * @param value true - ON, false - OFF
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ */
+ public native boolean setRTS(int handle, boolean value);
+
+ /**
+ * Change DTR line state
+ *
+ * @param handle handle of opened port
+ * @param value true - ON, false - OFF
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ */
+ public native boolean setDTR(int handle, boolean value);
+
+ /**
+ * Read data from port
+ *
+ * @param handle handle of opened port
+ * @param byteCount count of bytes required to read
+ *
+ * @return Method returns the array of read bytes
+ */
+ public native byte[] readBytes(int handle, int byteCount);
+
+ /**
+ * Write data to port
+ *
+ * @param handle handle of opened port
+ * @param buffer array of bytes to write
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ */
+ public native boolean writeBytes(int handle, byte[] buffer);
+
+ /**
+ * Get bytes count in buffers of port
+ *
+ * @param handle handle of opened port
+ *
+ * @return Method returns the array that contains info about bytes count in buffers:
+ *
element 0 - input buffer
+ *
element 1 - output buffer
+ *
+ * @since 0.8
+ */
+ public native int[] getBuffersBytesCount(int handle);
+
+ /**
+ * Set flow control mode
+ *
+ * @param handle handle of opened port
+ * @param mask mask of flow control mode
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @since 0.8
+ */
+ public native boolean setFlowControlMode(int handle, int mask);
+
+ /**
+ * Get flow control mode
+ *
+ * @param handle handle of opened port
+ *
+ * @return Mask of setted flow control mode
+ *
+ * @since 0.8
+ */
+ public native int getFlowControlMode(int handle);
+
+ /**
+ * Get serial port names like an array of String
+ *
+ * @return unsorted array of String with port names
+ */
+ public native String[] getSerialPortNames();
+
+ /**
+ * Getting lines states
+ *
+ * @param handle handle of opened port
+ *
+ * @return Method returns the array containing information about lines in following order:
+ *
element 0 - CTS line state
+ *
element 1 - DSR line state
+ *
element 2 - RING line state
+ *
element 3 - RLSD line state
+ */
+ public native int[] getLinesStatus(int handle);
+
+ /**
+ * Send Break singnal for setted duration
+ *
+ * @param handle handle of opened port
+ * @param duration duration of Break signal
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @since 0.8
+ */
+ public native boolean sendBreak(int handle, int duration);
+}
diff --git a/src/java/jssc/SerialPort.java b/src/java/jssc/SerialPort.java
new file mode 100644
index 0000000..6985f76
--- /dev/null
+++ b/src/java/jssc/SerialPort.java
@@ -0,0 +1,1118 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+package jssc;
+
+/**
+ *
+ * @author scream3r
+ */
+public class SerialPort {
+
+ private SerialNativeInterface serialInterface;
+ private SerialPortEventListener eventListener;
+ private int portHandle;
+ private String portName;
+ private boolean portOpened = false;
+ private boolean maskAssigned = false;
+ private boolean eventListenerAdded = false;
+
+
+ public static final int BAUDRATE_110 = 110;
+ public static final int BAUDRATE_300 = 300;
+ public static final int BAUDRATE_600 = 600;
+ public static final int BAUDRATE_1200 = 1200;
+ public static final int BAUDRATE_4800 = 4800;
+ public static final int BAUDRATE_9600 = 9600;
+ public static final int BAUDRATE_14400 = 14400;
+ public static final int BAUDRATE_19200 = 19200;
+ public static final int BAUDRATE_38400 = 38400;
+ public static final int BAUDRATE_57600 = 57600;
+ public static final int BAUDRATE_115200 = 115200;
+ public static final int BAUDRATE_128000 = 128000;
+ public static final int BAUDRATE_256000 = 256000;
+
+
+ public static final int DATABITS_5 = 5;
+ public static final int DATABITS_6 = 6;
+ public static final int DATABITS_7 = 7;
+ public static final int DATABITS_8 = 8;
+
+
+ public static final int STOPBITS_1 = 1;
+ public static final int STOPBITS_2 = 2;
+ public static final int STOPBITS_1_5 = 3;
+
+
+ public static final int PARITY_NONE = 0;
+ public static final int PARITY_ODD = 1;
+ public static final int PARITY_EVEN = 2;
+ public static final int PARITY_MARK = 3;
+ public static final int PARITY_SPACE = 4;
+
+
+ public static final int PURGE_RXABORT = 0x0002;
+ public static final int PURGE_RXCLEAR = 0x0008;
+ public static final int PURGE_TXABORT = 0x0001;
+ public static final int PURGE_TXCLEAR = 0x0004;
+
+
+ public static final int MASK_RXCHAR = 1;
+ public static final int MASK_RXFLAG = 2;
+ public static final int MASK_TXEMPTY = 4;
+ public static final int MASK_CTS = 8;
+ public static final int MASK_DSR = 16;
+ public static final int MASK_RLSD = 32;
+ public static final int MASK_BREAK = 64;
+ public static final int MASK_ERR = 128;
+ public static final int MASK_RING = 256;
+
+
+ //since 0.8 ->
+ public static final int FLOWCONTROL_NONE = 0;
+ public static final int FLOWCONTROL_RTSCTS_IN = 1;
+ public static final int FLOWCONTROL_RTSCTS_OUT = 2;
+ public static final int FLOWCONTROL_XONXOFF_IN = 4;
+ public static final int FLOWCONTROL_XONXOFF_OUT = 8;
+ //<- since 0.8
+
+ //since 0.8 ->
+ public static final int ERROR_FRAME = 0x0008;
+ public static final int ERROR_OVERRUN = 0x0002;
+ public static final int ERROR_PARITY = 0x0004;
+ //<- since 0.8
+
+ public SerialPort(String portName) {
+ this.portName = portName;
+ serialInterface = new SerialNativeInterface();
+ }
+
+ /**
+ * Getting port name under operation
+ *
+ * @return Method returns port name under operation as a String
+ */
+ public String getPortName(){
+ return portName;
+ }
+
+ /**
+ * Getting port state
+ *
+ * @return Method returns true if port is open, otherwise false
+ */
+ public boolean isOpened() {
+ return portOpened;
+ }
+
+ /**
+ * Port opening
+ *
+ * Note: If port busy TYPE_PORT_BUSY exception will be thrown.
+ * If port not found TYPE_PORT_NOT_FOUND exception will be thrown.
+ *
+ * @return If the operation is successfully completed, the method returns true
+ *
+ * @throws SerialPortException
+ */
+ public boolean openPort() throws SerialPortException {
+ if(portOpened){
+ throw new SerialPortException(portName, "openPort()", SerialPortException.TYPE_PORT_ALREADY_OPENED);
+ }
+ portHandle = serialInterface.openPort(portName);
+ //since 0.9.0 ->
+ if(portHandle == -1){
+ throw new SerialPortException(portName, "openPort()", SerialPortException.TYPE_PORT_BUSY);
+ }
+ else if(portHandle == -2){
+ throw new SerialPortException(portName, "openPort()", SerialPortException.TYPE_PORT_NOT_FOUND);
+ }
+ //<- since 0.9.0
+ portOpened = true;
+ return true;
+ }
+
+ /**
+ * Setting the parameters of port. RTS and DTR lines are enabled by default
+ *
+ * @param baudRate data transfer rate
+ * @param dataBits number of data bits
+ * @param stopBits number of stop bits
+ * @param parity parity
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean setParams(int baudRate, int dataBits, int stopBits, int parity) throws SerialPortException {
+ checkPortOpened("setParams()");
+ if(stopBits == 1){
+ stopBits = 0;
+ }
+ else if(stopBits == 3){
+ stopBits = 1;
+ }
+ return serialInterface.setParams(portHandle, baudRate, dataBits, stopBits, parity, true, true);
+ }
+
+ /**
+ * Setting the parameters of port
+ *
+ * @param baudRate data transfer rate
+ * @param dataBits number of data bits
+ * @param stopBits number of stop bits
+ * @param parity parity
+ * @param setRTS initial state of RTS line(ON/OFF)
+ * @param setDTR initial state of DTR line(ON/OFF)
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public boolean setParams(int baudRate, int dataBits, int stopBits, int parity, boolean setRTS, boolean setDTR) throws SerialPortException {
+ checkPortOpened("setParams()");
+ if(stopBits == 1){
+ stopBits = 0;
+ }
+ else if(stopBits == 3){
+ stopBits = 1;
+ }
+ return serialInterface.setParams(portHandle, baudRate, dataBits, stopBits, parity, setRTS, setDTR);
+ }
+
+ /**
+ * Purge of input and output buffer. Required flags shall be sent to the input. Variables with prefix
+ * "PURGE_", for example "PURGE_RXCLEAR". Sent parameter "flags" is additive value,
+ * so addition of flags is allowed. For example, if input or output buffer shall be purged,
+ * parameter "PURGE_RXCLEAR | PURGE_TXCLEAR".
+ *
Note: some devices or drivers may not support this function
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false.
+ *
+ * @throws SerialPortException
+ */
+ public boolean purgePort(int flags) throws SerialPortException {
+ checkPortOpened("purgePort()");
+ return serialInterface.purgePort(portHandle, flags);
+ }
+
+ /**
+ * Events mask for Linux OS
+ *
+ * @since 0.8
+ */
+ private int linuxMask;
+
+ /**
+ * Set events mask. Required flags shall be sent to the input. Variables with prefix
+ * "MASK_", shall be used as flags, for example "MASK_RXCHAR".
+ * Sent parameter "mask" is additive value, so addition of flags is allowed.
+ * For example if messages about data receipt and CTS and DSR status changing
+ * shall be received, it is required to set the mask - "MASK_RXCHAR | MASK_CTS | MASK_DSR"
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean setEventsMask(int mask) throws SerialPortException {
+ checkPortOpened("setEventsMask()");
+ if(SerialNativeInterface.getOsType() == SerialNativeInterface.OS_LINUX ||
+ SerialNativeInterface.getOsType() == SerialNativeInterface.OS_SOLARIS ||
+ SerialNativeInterface.getOsType() == SerialNativeInterface.OS_MAC_OS_X){//since 0.9.0
+ linuxMask = mask;
+ if(mask > 0){
+ maskAssigned = true;
+ }
+ else {
+ maskAssigned = false;
+ }
+ return true;
+ }
+ boolean returnValue = serialInterface.setEventsMask(portHandle, mask);
+ if(!returnValue){
+ throw new SerialPortException(portName, "setEventsMask()", SerialPortException.TYPE_CANT_SET_MASK);
+ }
+ if(mask > 0){
+ maskAssigned = true;
+ }
+ else {
+ maskAssigned = false;
+ }
+ return returnValue;
+ }
+
+ /**
+ * Getting events mask for the port
+ *
+ * @return Method returns events mask as int type variable. This variable is an additive value
+ *
+ * @throws SerialPortException
+ */
+ public int getEventsMask() throws SerialPortException {
+ checkPortOpened("getEventsMask()");
+ if(SerialNativeInterface.getOsType() == SerialNativeInterface.OS_LINUX ||
+ SerialNativeInterface.getOsType() == SerialNativeInterface.OS_SOLARIS ||
+ SerialNativeInterface.getOsType() == SerialNativeInterface.OS_MAC_OS_X){//since 0.9.0
+ return linuxMask;
+ }
+ return serialInterface.getEventsMask(portHandle);
+ }
+
+ /**
+ * Getting events mask for the port is Linux OS (for internal use)
+ *
+ * @since 0.8
+ */
+ private int getLinuxMask() {
+ return linuxMask;
+ }
+
+ /**
+ * Change RTS line state. Set "true" for switching ON and "false" for switching OFF RTS line
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean setRTS(boolean enabled) throws SerialPortException {
+ checkPortOpened("setRTS()");
+ return serialInterface.setRTS(portHandle, enabled);
+ }
+
+ /**
+ * Change DTR line state. Set "true" for switching ON and "false" for switching OFF DTR line
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean setDTR(boolean enabled) throws SerialPortException {
+ checkPortOpened("setDTR()");
+ return serialInterface.setDTR(portHandle, enabled);
+ }
+
+ /**
+ * Write byte array to port
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean writeBytes(byte[] buffer) throws SerialPortException {
+ checkPortOpened("writeBytes()");
+ return serialInterface.writeBytes(portHandle, buffer);
+ }
+
+ /**
+ * Write single byte to port
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public boolean writeByte(byte singleByte) throws SerialPortException {
+ checkPortOpened("writeByte()");
+ return writeBytes(new byte[]{singleByte});
+ }
+
+ /**
+ * Write String to port
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public boolean writeString(String string) throws SerialPortException {
+ checkPortOpened("writeString()");
+ return writeBytes(string.getBytes());
+ }
+
+ /**
+ * Write int value (in range from 0 to 255 (0x00 - 0xFF)) to port
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public boolean writeInt(int singleInt) throws SerialPortException {
+ checkPortOpened("writeInt()");
+ return writeBytes(new byte[]{(byte)singleInt});
+ }
+
+ /**
+ * Write int array (in range from 0 to 255 (0x00 - 0xFF)) to port
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public boolean writeIntArray(int[] buffer) throws SerialPortException {
+ checkPortOpened("writeIntArray()");
+ byte[] byteArray = new byte[buffer.length];
+ for(int i = 0; i < buffer.length; i++){
+ byteArray[i] = (byte)buffer[i];
+ }
+ return writeBytes(byteArray);
+ }
+
+ /**
+ * Read byte array from port
+ *
+ * @param byteCount count of bytes for reading
+ *
+ * @return byte array with "byteCount" length
+ *
+ * @throws SerialPortException
+ */
+ public byte[] readBytes(int byteCount) throws SerialPortException {
+ checkPortOpened("readBytes()");
+ return serialInterface.readBytes(portHandle, byteCount);
+ }
+
+ /**
+ * Read string from port
+ *
+ * @param byteCount count of bytes for reading
+ *
+ * @return byte array with "byteCount" length converted to String
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public String readString(int byteCount) throws SerialPortException {
+ checkPortOpened("readString()");
+ return new String(readBytes(byteCount));
+ }
+
+ /**
+ * Read Hex string from port (example: FF OA FF). Separator by default is a space
+ *
+ * @param byteCount count of bytes for reading
+ *
+ * @return byte array with "byteCount" length converted to Hexadecimal String
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public String readHexString(int byteCount) throws SerialPortException {
+ checkPortOpened("readHexString()");
+ return readHexString(byteCount, " ");
+ }
+
+ /**
+ * Read Hex string from port with setted separator (example if separator is "::": FF::OA::FF)
+ *
+ * @param byteCount count of bytes for reading
+ *
+ * @return byte array with "byteCount" length converted to Hexadecimal String
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public String readHexString(int byteCount, String separator) throws SerialPortException {
+ checkPortOpened("readHexString()");
+ String[] strBuffer = readHexStringArray(byteCount);
+ String returnString = "";
+ boolean insertSeparator = false;
+ for(String value : strBuffer){
+ if(insertSeparator){
+ returnString += separator;
+ }
+ returnString += value;
+ insertSeparator = true;
+ }
+ return returnString;
+ }
+
+ /**
+ * Read Hex String array from port
+ *
+ * @param byteCount count of bytes for reading
+ *
+ * @return String array with "byteCount" length and Hexadecimal String values
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public String[] readHexStringArray(int byteCount) throws SerialPortException {
+ checkPortOpened("readHexStringArray()");
+ int[] intBuffer = readIntArray(byteCount);
+ String[] strBuffer = new String[intBuffer.length];
+ for(int i = 0; i < intBuffer.length; i++){
+ String value = Integer.toHexString(intBuffer[i]).toUpperCase();
+ if(value.length() == 1) {
+ value = "0" + value;
+ }
+ strBuffer[i] = value;
+ }
+ return strBuffer;
+ }
+
+ /**
+ * Read int array from port
+ *
+ * @param byteCount count of bytes for reading
+ *
+ * @return int array with values in range from 0 to 255
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public int[] readIntArray(int byteCount) throws SerialPortException {
+ checkPortOpened("readIntArray()");
+ byte[] buffer = readBytes(byteCount);
+ int[] intBuffer = new int[buffer.length];
+ for(int i = 0; i < buffer.length; i++){
+ if(buffer[i] < 0){
+ intBuffer[i] = 256 + buffer[i];
+ }
+ else {
+ intBuffer[i] = buffer[i];
+ }
+ }
+ return intBuffer;
+ }
+
+ /**
+ * Read all available bytes from port like a byte array
+ *
+ * @return If input buffer is empty null will be returned, else byte array with all data from port
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public byte[] readBytes() throws SerialPortException {
+ checkPortOpened("readBytes()");
+ int byteCount = getInputBufferBytesCount();
+ if(byteCount <= 0){
+ return null;
+ }
+ return readBytes(byteCount);
+ }
+
+ /**
+ * Read all available bytes from port like a String
+ *
+ * @return If input buffer is empty null will be returned, else byte array with all data from port converted to String
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public String readString() throws SerialPortException {
+ checkPortOpened("readString()");
+ int byteCount = getInputBufferBytesCount();
+ if(byteCount <= 0){
+ return null;
+ }
+ return readString(byteCount);
+ }
+
+ /**
+ * Read all available bytes from port like a Hex String
+ *
+ * @return If input buffer is empty null will be returned, else byte array with all data from port converted to Hex String
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public String readHexString() throws SerialPortException {
+ checkPortOpened("readHexString()");
+ int byteCount = getInputBufferBytesCount();
+ if(byteCount <= 0){
+ return null;
+ }
+ return readHexString(byteCount);
+ }
+
+ /**
+ * Read all available bytes from port like a Hex String with setted separator
+ *
+ * @return If input buffer is empty null will be returned, else byte array with all data from port converted to Hex String
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public String readHexString(String separator) throws SerialPortException {
+ checkPortOpened("readHexString()");
+ int byteCount = getInputBufferBytesCount();
+ if(byteCount <= 0){
+ return null;
+ }
+ return readHexString(byteCount, separator);
+ }
+
+ /**
+ * Read all available bytes from port like a Hex String array
+ *
+ * @return If input buffer is empty null will be returned, else byte array with all data from port converted to Hex String array
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public String[] readHexStringArray() throws SerialPortException {
+ checkPortOpened("readHexStringArray()");
+ int byteCount = getInputBufferBytesCount();
+ if(byteCount <= 0){
+ return null;
+ }
+ return readHexStringArray(byteCount);
+ }
+
+ /**
+ * Read all available bytes from port like a int array (values in range from 0 to 255)
+ *
+ * @return If input buffer is empty null will be returned, else byte array with all data from port converted to int array
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public int[] readIntArray() throws SerialPortException {
+ checkPortOpened("readHex()");
+ int byteCount = getInputBufferBytesCount();
+ if(byteCount <= 0){
+ return null;
+ }
+ return readIntArray(byteCount);
+ }
+
+ /**
+ * Get count of bytes in input buffer
+ *
+ * @return Count of bytes in input buffer or -1 if error occured
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public int getInputBufferBytesCount() throws SerialPortException {
+ checkPortOpened("getInputBufferBytesCount()");
+ return serialInterface.getBuffersBytesCount(portHandle)[0];
+ }
+
+ /**
+ * Get count of bytes in output buffer
+ *
+ * @return Count of bytes in output buffer or -1 if error occured
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public int getOutputBufferBytesCount() throws SerialPortException {
+ checkPortOpened("getOutputBufferBytesCount()");
+ return serialInterface.getBuffersBytesCount(portHandle)[1];
+ }
+
+ /**
+ * Set flow control mode. For required mode use variables with prefix "FLOWCONTROL_".
+ * Example of hardware flow control mode(RTS/CTS): setFlowControlMode(FLOWCONTROL_RTSCTS_IN | FLOWCONTROL_RTSCTS_OUT);
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public boolean setFlowControlMode(int mask) throws SerialPortException {
+ checkPortOpened("setFlowControlMode()");
+ return serialInterface.setFlowControlMode(portHandle, mask);
+ }
+
+ /**
+ * Get flow control mode
+ *
+ * @return Mask of setted flow control mode
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public int getFlowControlMode() throws SerialPortException {
+ checkPortOpened("getFlowControlMode()");
+ return serialInterface.getFlowControlMode(portHandle);
+ }
+
+ /**
+ * Send Break singnal for setted duration
+ *
+ * @param duration duration of Break signal
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ *
+ * @since 0.8
+ */
+ public boolean sendBreak(int duration)throws SerialPortException {
+ checkPortOpened("sendBreak()");
+ return serialInterface.sendBreak(portHandle, duration);
+ }
+
+ private int[][] waitEvents() {
+ return serialInterface.waitEvents(portHandle);
+ }
+
+ /**
+ * Check port opened (since jSSC-0.8 String "EMPTY" was replaced with "portName" variable)
+ *
+ * @param methodName method name
+ *
+ * @throws SerialPortException
+ */
+ private void checkPortOpened(String methodName) throws SerialPortException {
+ if(!portOpened){
+ throw new SerialPortException(portName, methodName, SerialPortException.TYPE_PORT_NOT_OPENED);
+ }
+ }
+
+ /**
+ * Getting lines status. Lines status is sent as 0 – OFF and 1 - ON
+ *
+ * @return Method returns the array containing information about lines in following order:
+ *
element 0 - CTS line state
+ *
element 1 - DSR line state
+ *
element 2 - RING line state
+ *
element 3 - RLSD line state
+ *
+ * @throws SerialPortException
+ */
+ public int[] getLinesStatus() throws SerialPortException {
+ checkPortOpened("getLinesStatus()");
+ return serialInterface.getLinesStatus(portHandle);
+ }
+
+ /**
+ * Get state of CTS line
+ *
+ * @return If line is active, method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean isCTS() throws SerialPortException {
+ checkPortOpened("isCTS()");
+ if(serialInterface.getLinesStatus(portHandle)[0] == 1){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Get state of DSR line
+ *
+ * @return If line is active, method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean isDSR() throws SerialPortException {
+ checkPortOpened("isDSR()");
+ if(serialInterface.getLinesStatus(portHandle)[1] == 1){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Get state of RING line
+ *
+ * @return If line is active, method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean isRING() throws SerialPortException {
+ checkPortOpened("isRING()");
+ if(serialInterface.getLinesStatus(portHandle)[2] == 1){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Get state of RLSD line
+ *
+ * @return If line is active, method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean isRLSD() throws SerialPortException {
+ checkPortOpened("isRLSD()");
+ if(serialInterface.getLinesStatus(portHandle)[3] == 1){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Add event listener. Object of "SerialPortEventListener" type shall
+ * be sent to the method. This object shall be properly described, as it will
+ * be in charge for handling of occurred events. This method will independently
+ * set the mask in "MASK_RXCHAR" state if it was not set beforehand
+ *
+ * @throws SerialPortException
+ */
+ public void addEventListener(SerialPortEventListener listener) throws SerialPortException {
+ checkPortOpened("addEventListener()");
+ if(!eventListenerAdded){
+ if(maskAssigned){
+ eventListener = listener;
+ eventThread = getNewEventThread();
+ eventThread.setName("EventThread " + portName);
+ eventThread.start();
+ eventListenerAdded = true;
+ }
+ else {
+ setEventsMask(MASK_RXCHAR);
+ eventListener = listener;
+ eventThread = getNewEventThread();
+ eventThread.setName("EventThread " + portName);
+ eventThread.start();
+ eventListenerAdded = true;
+ }
+ }
+ else {
+ throw new SerialPortException(portName, "addEventListener()", SerialPortException.TYPE_LISTENER_ALREADY_ADDED);
+ }
+ }
+
+ /**
+ * Add event listener. Object of "SerialPortEventListener" type shall be sent
+ * to the method. This object shall be properly described, as it will be in
+ * charge for handling of occurred events. Also events mask shall be sent to
+ * this method, to do it use variables with prefix "MASK_" for example "MASK_RXCHAR"
+ *
+ * @see #setEventsMask(int) setEventsMask(int mask)
+ *
+ * @throws SerialPortException
+ */
+ public void addEventListener(SerialPortEventListener listener, int mask) throws SerialPortException {
+ checkPortOpened("addEventListener()");
+ if(!eventListenerAdded){
+ setEventsMask(mask);
+ eventListener = listener;
+ eventThread = getNewEventThread();
+ eventThread.setName("EventThread " + portName);
+ eventThread.start();
+ eventListenerAdded = true;
+ }
+ else {
+ throw new SerialPortException(portName, "addEventListener()", SerialPortException.TYPE_LISTENER_ALREADY_ADDED);
+ }
+ }
+
+ /**
+ * Create new EventListener Thread depending on the type of operating system
+ *
+ * @since 0.8
+ */
+ private EventThread getNewEventThread() {
+ if(SerialNativeInterface.getOsType() == SerialNativeInterface.OS_LINUX ||
+ SerialNativeInterface.getOsType() == SerialNativeInterface.OS_SOLARIS ||
+ SerialNativeInterface.getOsType() == SerialNativeInterface.OS_MAC_OS_X){//since 0.9.0
+ return new LinuxEventThread();
+ }
+ return new EventThread();
+ }
+
+ /**
+ * Delete event listener. Mask is set to 0. So at the next addition of event
+ * handler you shall set required event mask again
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean removeEventListener() throws SerialPortException {
+ checkPortOpened("removeEventListener()");
+ if(!eventListenerAdded){
+ throw new SerialPortException(portName, "removeEventListener()", SerialPortException.TYPE_CANT_REMOVE_LISTENER);
+ }
+ eventThread.terminateThread();
+ setEventsMask(0);
+ if(Thread.currentThread().getId() != eventThread.getId()){
+ if(eventThread.isAlive()){
+ try {
+ eventThread.join(5000);
+ }
+ catch (InterruptedException ex) {
+ throw new SerialPortException(portName, "removeEventListener()", SerialPortException.TYPE_LISTENER_THREAD_INTERRUPTED);
+ }
+ }
+ }
+ eventListenerAdded = false;
+ return true;
+ }
+
+ /**
+ * Close port. This method deletes event listener first, then closes the port
+ *
+ * @return If the operation is successfully completed, the method returns true, otherwise false
+ *
+ * @throws SerialPortException
+ */
+ public boolean closePort() throws SerialPortException {
+ checkPortOpened("closePort()");
+ if(eventListenerAdded){
+ removeEventListener();
+ }
+ boolean returnValue = serialInterface.closePort(portHandle);
+ if(returnValue){
+ maskAssigned = false;
+ portOpened = false;
+ }
+ return returnValue;
+ }
+
+ private EventThread eventThread;
+
+ private class EventThread extends Thread {
+
+ private boolean threadTerminated = false;
+
+ @Override
+ public void run() {
+ while(!threadTerminated){
+ int[][] eventArray = waitEvents();
+ for(int i = 0; i < eventArray.length; i++){
+ if(eventArray[i][0] > 0 && !threadTerminated){
+ eventListener.serialEvent(new SerialPortEvent(portName, eventArray[i][0], eventArray[i][1]));
+ }
+ }
+ }
+ }
+
+ private void terminateThread(){
+ threadTerminated = true;
+ }
+ }
+
+ /**
+ * EventListener for Linux OS
+ *
+ * @since 0.8
+ */
+ private class LinuxEventThread extends EventThread {
+
+ //Essential interruptions for events: BREAK, ERR, TXEMPTY
+ private final int INTERRUPT_BREAK = 512;
+ private final int INTERRUPT_TX = 1024;
+ private final int INTERRUPT_FRAME = 2048;
+ private final int INTERRUPT_OVERRUN = 4096;
+ private final int INTERRUPT_PARITY = 8192;
+
+ //Count of interruptions
+ private int interruptBreak;
+ private int interruptTX;
+ private int interruptFrame;
+ private int interruptOverrun;
+ private int interruptParity;
+
+ //Previous states if lines (then state change event will be generated)
+ private int preCTS;
+ private int preDSR;
+ private int preRLSD;
+ private int preRING;
+
+ //Need to get initial states
+ public LinuxEventThread(){
+ int[][] eventArray = waitEvents();
+ for(int i = 0; i < eventArray.length; i++){
+ int eventType = eventArray[i][0];
+ int eventValue = eventArray[i][1];
+ switch(eventType){
+ case INTERRUPT_BREAK:
+ interruptBreak = eventValue;
+ break;
+ case INTERRUPT_TX:
+ interruptTX = eventValue;
+ break;
+ case INTERRUPT_FRAME:
+ interruptFrame = eventValue;
+ break;
+ case INTERRUPT_OVERRUN:
+ interruptOverrun = eventValue;
+ break;
+ case INTERRUPT_PARITY:
+ interruptParity = eventValue;
+ break;
+ case MASK_CTS:
+ preCTS = eventValue;
+ break;
+ case MASK_DSR:
+ preDSR = eventValue;
+ break;
+ case MASK_RING:
+ preRING = eventValue;
+ break;
+ case MASK_RLSD:
+ preRLSD = eventValue;
+ break;
+ }
+ }
+ }
+
+ @Override
+ public void run() {
+ while(!super.threadTerminated){
+ int[][] eventArray = waitEvents();
+ int mask = getLinuxMask();
+ boolean interruptTxChanged = false;
+ int errorMask = 0;
+ for(int i = 0; i < eventArray.length; i++){
+ boolean sendEvent = false;
+ int eventType = eventArray[i][0];
+ int eventValue = eventArray[i][1];
+ if(eventType > 0 && !super.threadTerminated){
+ switch(eventType){
+ case INTERRUPT_BREAK:
+ if(eventValue != interruptBreak){
+ interruptBreak = eventValue;
+ if((mask & MASK_BREAK) == MASK_BREAK){
+ eventType = MASK_BREAK;
+ eventValue = 0;
+ sendEvent = true;
+ }
+ }
+ break;
+ case INTERRUPT_TX:
+ if(eventValue != interruptTX){
+ interruptTX = eventValue;
+ interruptTxChanged = true;
+ }
+ break;
+ case INTERRUPT_FRAME:
+ if(eventValue != interruptFrame){
+ interruptFrame = eventValue;
+ errorMask |= ERROR_FRAME;
+ }
+ break;
+ case INTERRUPT_OVERRUN:
+ if(eventValue != interruptOverrun){
+ interruptOverrun = eventValue;
+ errorMask |= ERROR_OVERRUN;
+ }
+ break;
+ case INTERRUPT_PARITY:
+ if(eventValue != interruptParity){
+ interruptParity = eventValue;
+ errorMask |= ERROR_PARITY;
+ }
+ if((mask & MASK_ERR) == MASK_ERR && errorMask != 0){
+ eventType = MASK_ERR;
+ eventValue = errorMask;
+ sendEvent = true;
+ }
+ break;
+ case MASK_CTS:
+ if(eventValue != preCTS){
+ preCTS = eventValue;
+ if((mask & MASK_CTS) == MASK_CTS){
+ sendEvent = true;
+ }
+ }
+ break;
+ case MASK_DSR:
+ if(eventValue != preDSR){
+ preDSR = eventValue;
+ if((mask & MASK_DSR) == MASK_DSR){
+ sendEvent = true;
+ }
+ }
+ break;
+ case MASK_RING:
+ if(eventValue != preRING){
+ preRING = eventValue;
+ if((mask & MASK_RING) == MASK_RING){
+ sendEvent = true;
+ }
+ }
+ break;
+ case MASK_RLSD: /*DCD*/
+ if(eventValue != preRLSD){
+ preRLSD = eventValue;
+ if((mask & MASK_RLSD) == MASK_RLSD){
+ sendEvent = true;
+ }
+ }
+ break;
+ case MASK_RXCHAR:
+ if(((mask & MASK_RXCHAR) == MASK_RXCHAR) && (eventValue > 0)){
+ sendEvent = true;
+ }
+ break;
+ /*case MASK_RXFLAG:
+ //Do nothing at this moment
+ if(((mask & MASK_RXFLAG) == MASK_RXFLAG) && (eventValue > 0)){
+ sendEvent = true;
+ }
+ break;*/
+ case MASK_TXEMPTY:
+ if(((mask & MASK_TXEMPTY) == MASK_TXEMPTY) && (eventValue == 0) && interruptTxChanged){
+ sendEvent = true;
+ }
+ break;
+ }
+ if(sendEvent){
+ eventListener.serialEvent(new SerialPortEvent(portName, eventType, eventValue));
+ }
+ }
+ }
+ //Need to sleep some time
+ try {
+ Thread.sleep(0, 100);
+ }
+ catch (Exception ex) {
+ //Do nothing
+ }
+ }
+ }
+ }
+}
diff --git a/src/java/jssc/SerialPortEvent.java b/src/java/jssc/SerialPortEvent.java
new file mode 100644
index 0000000..19f69ae
--- /dev/null
+++ b/src/java/jssc/SerialPortEvent.java
@@ -0,0 +1,192 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+package jssc;
+
+/**
+ *
+ * @author scream3r
+ */
+public class SerialPortEvent {
+
+ private String portName;
+ private int eventType;
+ private int eventValue;
+
+ public static final int RXCHAR = 1;
+ public static final int RXFLAG = 2;
+ public static final int TXEMPTY = 4;
+ public static final int CTS = 8;
+ public static final int DSR = 16;
+ public static final int RLSD = 32;
+ public static final int BREAK = 64;
+ public static final int ERR = 128;
+ public static final int RING = 256;
+
+ public SerialPortEvent(String portName, int eventType, int eventValue){
+ this.portName = portName;
+ this.eventType = eventType;
+ this.eventValue = eventValue;
+ }
+
+ /**
+ * Getting port name which sent the event
+ */
+ public String getPortName() {
+ return portName;
+ }
+
+ /**
+ * Getting event type
+ */
+ public int getEventType() {
+ return eventType;
+ }
+
+ /**
+ * Getting event value
+ *
+ *
Event values depending on their types:
+ *
RXCHAR - bytes count in input buffer
+ *
RXFLAG - bytes count in input buffer (Not supported in Linux)
+ *
TXEMPTY - bytes count in output buffer
+ *
CTS - state of CTS line (0 - OFF, 1 - ON)
+ *
DSR - state of DSR line (0 - OFF, 1 - ON)
+ *
RLSD - state of RLSD line (0 - OFF, 1 - ON)
+ *
BREAK - 0
+ *
RING - state of RING line (0 - OFF, 1 - ON)
+ *
ERR - mask of errors
+ */
+ public int getEventValue() {
+ return eventValue;
+ }
+
+ /**
+ * Method returns true if event of type "RXCHAR" is received and otherwise false
+ */
+ public boolean isRXCHAR() {
+ if(eventType == RXCHAR){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Method returns true if event of type "RXFLAG" is received and otherwise false
+ */
+ public boolean isRXFLAG() {
+ if(eventType == RXFLAG){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Method returns true if event of type "TXEMPTY" is received and otherwise false
+ */
+ public boolean isTXEMPTY() {
+ if(eventType == TXEMPTY){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Method returns true if event of type "CTS" is received and otherwise false
+ */
+ public boolean isCTS() {
+ if(eventType == CTS){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Method returns true if event of type "DSR" is received and otherwise false
+ */
+ public boolean isDSR() {
+ if(eventType == DSR){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Method returns true if event of type "RLSD" is received and otherwise false
+ */
+ public boolean isRLSD() {
+ if(eventType == RLSD){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Method returns true if event of type "BREAK" is received and otherwise false
+ */
+ public boolean isBREAK() {
+ if(eventType == BREAK){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Method returns true if event of type "ERR" is received and otherwise false
+ */
+ public boolean isERR() {
+ if(eventType == ERR){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+
+ /**
+ * Method returns true if event of type "RING" is received and otherwise false
+ */
+ public boolean isRING() {
+ if(eventType == RING){
+ return true;
+ }
+ else {
+ return false;
+ }
+ }
+}
diff --git a/src/java/jssc/SerialPortEventListener.java b/src/java/jssc/SerialPortEventListener.java
new file mode 100644
index 0000000..d7214e7
--- /dev/null
+++ b/src/java/jssc/SerialPortEventListener.java
@@ -0,0 +1,34 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+package jssc;
+
+/**
+ *
+ * @author scream3r
+ */
+public interface SerialPortEventListener {
+
+ public abstract void serialEvent(SerialPortEvent serialPortEvent);
+}
diff --git a/src/java/jssc/SerialPortException.java b/src/java/jssc/SerialPortException.java
new file mode 100644
index 0000000..0d1c100
--- /dev/null
+++ b/src/java/jssc/SerialPortException.java
@@ -0,0 +1,87 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+package jssc;
+
+/**
+ *
+ * @author scream3r
+ */
+public class SerialPortException extends Exception {
+
+ final public static String TYPE_PORT_ALREADY_OPENED = "Port already opened";
+ final public static String TYPE_PORT_NOT_OPENED = "Port not opened";
+ final public static String TYPE_CANT_SET_MASK = "Can't set mask";
+ final public static String TYPE_LISTENER_ALREADY_ADDED = "Event listener already added";
+ final public static String TYPE_LISTENER_THREAD_INTERRUPTED = "Event listener thread interrupted";
+ final public static String TYPE_CANT_REMOVE_LISTENER = "Can't remove event listener, because listener not added";
+ /**
+ * @since 0.8
+ */
+ final public static String TYPE_PARAMETER_IS_NOT_CORRECT = "Parameter is not correct";
+ /**
+ * @since 0.8
+ */
+ final public static String TYPE_NULL_NOT_PERMITTED = "Null not permitted";
+ /**
+ * @since 0.9.0
+ */
+ final public static String TYPE_PORT_BUSY = "Port busy";
+ /**
+ * @since 0.9.0
+ */
+ final public static String TYPE_PORT_NOT_FOUND = "Port not found";
+
+ private String portName;
+ private String methodName;
+ private String exceptionType;
+
+ public SerialPortException(String portName, String methodName, String exceptionType){
+ super("Port name - " + portName + "; Method name - " + methodName + "; Exception type - " + exceptionType + ".");
+ this.portName = portName;
+ this.methodName = methodName;
+ this.exceptionType = exceptionType;
+ }
+
+ /**
+ * Getting port name during operation with which the exception was called
+ */
+ public String getPortName(){
+ return portName;
+ }
+
+ /**
+ * Getting method name during execution of which the exception was called
+ */
+ public String getMethodName(){
+ return methodName;
+ }
+
+ /**
+ * Getting exception type
+ */
+ public String getExceptionType(){
+ return exceptionType;
+ }
+}
diff --git a/src/java/jssc/SerialPortList.java b/src/java/jssc/SerialPortList.java
new file mode 100644
index 0000000..513181c
--- /dev/null
+++ b/src/java/jssc/SerialPortList.java
@@ -0,0 +1,194 @@
+/* jSSC (Java Simple Serial Connector) - serial port communication library.
+ * © Alexey Sokolov (scream3r), 2010-2011.
+ *
+ * This file is part of jSSC.
+ *
+ * jSSC 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 3 of the License, or
+ * (at your option) any later version.
+ *
+ * jSSC 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 jSSC. If not, see .
+ *
+ * If you use jSSC in public project you can inform me about this by e-mail,
+ * of course if you want it.
+ *
+ * e-mail: scream3r.org@gmail.com
+ * web-site: http://scream3r.org | http://code.google.com/p/java-simple-serial-connector/
+ */
+package jssc;
+
+import java.io.BufferedReader;
+import java.io.File;
+import java.io.IOException;
+import java.io.InputStreamReader;
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.Comparator;
+import java.util.TreeSet;
+
+/**
+ *
+ * @author scream3r
+ */
+public class SerialPortList {
+
+ private static SerialNativeInterface serialInterface;
+ private static Comparator comparator = new Comparator() {
+ @Override
+ public int compare(String valueA, String valueB) {
+ int result = 0;
+ if(valueA.toLowerCase().contains("com") && valueB.toLowerCase().contains("com")){
+ try {
+ int index1 = Integer.valueOf(valueA.toLowerCase().replace("com", ""));
+ int index2 = Integer.valueOf(valueB.toLowerCase().replace("com", ""));
+ result = index1 - index2;
+ }
+ catch (Exception ex) {
+ result = valueA.compareToIgnoreCase(valueB);
+ }
+ }
+ else {
+ result = valueA.compareToIgnoreCase(valueB);
+ }
+ return result;
+ }
+ };
+
+ static {
+ serialInterface = new SerialNativeInterface();
+ }
+
+ /**
+ * Get sorted array of serial ports in the system
+ *
+ * @return String array. If there is no ports in the system String[]
+ * with zero length will be returned (since jSSC-0.8 in previous versions null will be returned)
+ */
+ public static String[] getPortNames() {
+ if(SerialNativeInterface.getOsType() == SerialNativeInterface.OS_LINUX){
+ return getLinuxPortNames();
+ }
+ else if(SerialNativeInterface.getOsType() == SerialNativeInterface.OS_SOLARIS){//since 0.9.0 ->
+ return getSolarisPortNames();
+ }
+ else if(SerialNativeInterface.getOsType() == SerialNativeInterface.OS_MAC_OS_X){
+ return getMacOSXPortNames();
+ }//<-since 0.9.0
+ String[] portNames = serialInterface.getSerialPortNames();
+ if(portNames == null){
+ return new String[]{};
+ }
+ TreeSet ports = new TreeSet(comparator);
+ ports.addAll(Arrays.asList(portNames));
+ return ports.toArray(new String[ports.size()]);
+ }
+
+ /**
+ * Get serial port names in Linux OS (This method was completely rewrited in 0.8-tb4)
+ *
+ * @return
+ */
+ private static String[] getLinuxPortNames() {
+ String[] returnArray = new String[]{};
+ try {
+ Process dmesgProcess = Runtime.getRuntime().exec("dmesg");
+ BufferedReader reader = new BufferedReader(new InputStreamReader(dmesgProcess.getInputStream()));
+ TreeSet portsTree = new TreeSet();
+ ArrayList portsList = new ArrayList();
+ String buffer = "";
+ while((buffer = reader.readLine()) != null && !buffer.isEmpty()){
+ if(buffer.matches(".*(ttyS|ttyUSB)[0-9]{1,3}.*")){
+ String[] tmp = buffer.split(" ");
+ for(String value : tmp){
+ if(value.matches("(ttyS|ttyUSB)[0-9]{1,3}")){
+ portsTree.add("/dev/" + value);
+ }
+ }
+ }
+ }
+ for(String portName : portsTree){
+ SerialPort serialPort = new SerialPort(portName);
+ try {
+ if(serialPort.openPort()){
+ portsList.add(portName);
+ serialPort.closePort();
+ }
+ }
+ catch (SerialPortException ex) {
+ //since 0.9.0 ->
+ if(ex.getExceptionType().equals(SerialPortException.TYPE_PORT_BUSY)){
+ portsList.add(portName);
+ }
+ //<- since 0.9.0
+ }
+ }
+ returnArray = portsList.toArray(returnArray);
+ reader.close();
+ }
+ catch (IOException ex) {
+ //Do nothing
+ }
+ return returnArray;
+ }
+
+ /**
+ * Get serial port names in Solaris OS
+ *
+ * @since 0.9.0
+ */
+ private static String[] getSolarisPortNames() {
+ String[] returnArray = new String[]{};
+ File dir = new File("/dev/term");
+ if(dir.exists() && dir.isDirectory()){
+ File[] files = dir.listFiles();
+ if(files.length > 0){
+ TreeSet portsTree = new TreeSet();
+ ArrayList portsList = new ArrayList();
+ for(File file : files){
+ if(!file.isDirectory() && !file.isFile() && file.getName().matches("[0-9]*|[a-z]*")){
+ portsTree.add("/dev/term/" + file.getName());
+ }
+ }
+ for(String portName : portsTree){
+ portsList.add(portName);
+ }
+ returnArray = portsList.toArray(returnArray);
+ }
+ }
+ return returnArray;
+ }
+
+ /**
+ * Get serial port names in Mac OS X
+ *
+ * @since 0.9.0
+ */
+ private static String[] getMacOSXPortNames() {
+ String[] returnArray = new String[]{};
+ File dir = new File("/dev");
+ if(dir.exists() && dir.isDirectory()){
+ File[] files = dir.listFiles();
+ if(files.length > 0){
+ TreeSet portsTree = new TreeSet();
+ ArrayList portsList = new ArrayList();
+ for(File file : files){
+ if(!file.isDirectory() && !file.isFile() && file.getName().matches("tty.(serial.*|usbserial.*)")){
+ portsTree.add("/dev/" + file.getName());
+ }
+ }
+ for(String portName : portsTree){
+ portsList.add(portName);
+ }
+ returnArray = portsList.toArray(returnArray);
+ }
+ }
+ return returnArray;
+ }
+}
diff --git a/src/java/libs/linux/libjSSC-0.9_x86.so b/src/java/libs/linux/libjSSC-0.9_x86.so
new file mode 100644
index 0000000..fa08c40
Binary files /dev/null and b/src/java/libs/linux/libjSSC-0.9_x86.so differ
diff --git a/src/java/libs/linux/libjSSC-0.9_x86_64.so b/src/java/libs/linux/libjSSC-0.9_x86_64.so
new file mode 100644
index 0000000..2639593
Binary files /dev/null and b/src/java/libs/linux/libjSSC-0.9_x86_64.so differ
diff --git a/src/java/libs/mac_os_x/libjSSC-0.9_ppc.jnilib b/src/java/libs/mac_os_x/libjSSC-0.9_ppc.jnilib
new file mode 100644
index 0000000..27b8694
Binary files /dev/null and b/src/java/libs/mac_os_x/libjSSC-0.9_ppc.jnilib differ
diff --git a/src/java/libs/mac_os_x/libjSSC-0.9_ppc64.jnilib b/src/java/libs/mac_os_x/libjSSC-0.9_ppc64.jnilib
new file mode 100644
index 0000000..96319f6
Binary files /dev/null and b/src/java/libs/mac_os_x/libjSSC-0.9_ppc64.jnilib differ
diff --git a/src/java/libs/mac_os_x/libjSSC-0.9_x86.jnilib b/src/java/libs/mac_os_x/libjSSC-0.9_x86.jnilib
new file mode 100644
index 0000000..025becf
Binary files /dev/null and b/src/java/libs/mac_os_x/libjSSC-0.9_x86.jnilib differ
diff --git a/src/java/libs/mac_os_x/libjSSC-0.9_x86_64.jnilib b/src/java/libs/mac_os_x/libjSSC-0.9_x86_64.jnilib
new file mode 100644
index 0000000..393cfd5
Binary files /dev/null and b/src/java/libs/mac_os_x/libjSSC-0.9_x86_64.jnilib differ
diff --git a/src/java/libs/solaris/libjSSC-0.9_x86.so b/src/java/libs/solaris/libjSSC-0.9_x86.so
new file mode 100644
index 0000000..1a2b6af
Binary files /dev/null and b/src/java/libs/solaris/libjSSC-0.9_x86.so differ
diff --git a/src/java/libs/solaris/libjSSC-0.9_x86_64.so b/src/java/libs/solaris/libjSSC-0.9_x86_64.so
new file mode 100644
index 0000000..931b44c
Binary files /dev/null and b/src/java/libs/solaris/libjSSC-0.9_x86_64.so differ
diff --git a/src/java/libs/windows/jSSC-0.9_x86.dll b/src/java/libs/windows/jSSC-0.9_x86.dll
new file mode 100644
index 0000000..9f0fcec
Binary files /dev/null and b/src/java/libs/windows/jSSC-0.9_x86.dll differ
diff --git a/src/java/libs/windows/jSSC-0.9_x86_64.dll b/src/java/libs/windows/jSSC-0.9_x86_64.dll
new file mode 100644
index 0000000..bb3cb2f
Binary files /dev/null and b/src/java/libs/windows/jSSC-0.9_x86_64.dll differ