serialcomm.cpp
Go to the documentation of this file.
00001 /*
00002  * serialcomm.cpp
00003  *
00004  *  Created on: June 05, 2012
00005  *      Author: mwalecki
00006  */
00007 
00008 #include <math.h>
00009 #include <unistd.h>
00010 #include <fcntl.h>
00011 #include <sys/types.h>
00012 #include <sys/stat.h>
00013 #include <cstring>
00014 #include <iostream>
00015 
00016 #include "serialcomm.hpp"
00017 
00018 using namespace std;
00019 
00020 SerialComm::SerialComm(const std::string& port, int baud) {
00021         connected = false;
00022 
00023         fd = open(port.c_str(), O_RDWR | O_NOCTTY | O_NDELAY);
00024         if (fd >= 0) {
00025                 tcgetattr(fd, &oldtio);
00026 
00027                 // set up new settings
00028                 struct termios newtio;
00029                 memset(&newtio, 0, sizeof(newtio));
00030                 newtio.c_cflag = CBAUD | CS8 | CLOCAL | CREAD | CSTOPB;
00031                 newtio.c_iflag = INPCK | IGNPAR;
00032                 newtio.c_oflag = 0;
00033                 newtio.c_lflag = 0;
00034                 //newtio.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); //####
00035                 if (cfsetispeed(&newtio, baud) < 0 || cfsetospeed(&newtio, baud) < 0) {
00036                         fprintf(stderr, "Failed to set serial baud rate: %d\n", baud);
00037                         tcsetattr(fd, TCSANOW, &oldtio);
00038                         close(fd);
00039                         fd = -1;
00040                         return;
00041                 }
00042                 // activate new settings
00043                 tcflush(fd, TCIFLUSH);
00044                 tcsetattr(fd, TCSANOW, &newtio);
00045                 //fcntl(fd, F_SETFL, FNDELAY);  //####
00046                 connected = true;
00047         }
00048 }
00049 
00050 SerialComm::~SerialComm() {
00051         // restore old port settings
00052         if (fd > 0)
00053                 tcsetattr(fd, TCSANOW, &oldtio);
00054         close(fd);
00055 }
00056 
00057 int SerialComm::write(uint8_t* buf, int len) {
00058         tcflush(fd, TCIFLUSH);
00059         return ::write(fd, buf, len);
00060 }
00061 
00062 int SerialComm::read(uint8_t* buf, int len) {
00063         return ::read(fd, (char*) buf, len);
00064 }
00065 
00066 uint8_t SerialComm::readOneByte() {
00067         uint8_t ret;
00068         int sel;
00069         struct timeval tv;
00070 
00071         // Prepare mask for select - Watch fd to see when it has input
00072         FD_ZERO(&rfds);
00073         FD_SET(fd, &rfds);
00074         do {
00075                 printf("Read attempt.\n");
00076                 // Prepare imeout struct for select - Wait up to five seconds
00077                 tv.tv_sec = 5;
00078                 tv.tv_usec = 0;
00079         
00080                 sel = select(fd+1, &rfds, NULL, NULL, &tv);
00081                 // Don't rely on the value of tv now!
00082 
00083                 if (sel == -1)
00084                         perror("select()");
00085                 else if (sel == 0)
00086                         printf("No data within five seconds.\n");
00087         } while( ::read(fd, (char*)(&ret), 1) < 1);
00088         return ret;
00089 }
00090 
00091 bool SerialComm::isConnected() {
00092         return connected?true:false;
00093 }
00094 


elektron_base
Author(s): Konrad Banachowicz
autogenerated on Mon Oct 6 2014 10:26:31