serialIO.cpp
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2010
00004  *
00005  * Fraunhofer Institute for Manufacturing Engineering   
00006  * and Automation (IPA)
00007  *
00008  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009  *
00010  * Project name: care-o-bot
00011  * ROS stack name: cob_driver
00012  * ROS package name: cob_light
00013  * Description: Switch robots led color by sending data to
00014  * the led-µC over serial connection.
00015  *                                                              
00016  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00017  *                      
00018  * Author: Benjamin Maidel, email:benjamin.maidel@ipa.fraunhofer.de
00019  * Supervised by: Benjamin Maidel, email:benjamin.maidel@ipa.fraunhofer.de
00020  *
00021  * Date of creation: August 2012
00022  * ToDo:
00023  *
00024  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00025  *
00026  * Redistribution and use in source and binary forms, with or without
00027  * modification, are permitted provided that the following conditions are met:
00028  *
00029  *     * Redistributions of source code must retain the above copyright
00030  *       notice, this list of conditions and the following disclaimer.
00031  *     * Redistributions in binary form must reproduce the above copyright
00032  *       notice, this list of conditions and the following disclaimer in the
00033  *       documentation and/or other materials provided with the distribution.
00034  *     * Neither the name of the Fraunhofer Institute for Manufacturing 
00035  *       Engineering and Automation (IPA) nor the names of its
00036  *       contributors may be used to endorse or promote products derived from
00037  *       this software without specific prior written permission.
00038  *
00039  * This program is free software: you can redistribute it and/or modify
00040  * it under the terms of the GNU Lesser General Public License LGPL as 
00041  * published by the Free Software Foundation, either version 3 of the 
00042  * License, or (at your option) any later version.
00043  * 
00044  * This program is distributed in the hope that it will be useful,
00045  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00046  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00047  * GNU Lesser General Public License LGPL for more details.
00048  * 
00049  * You should have received a copy of the GNU Lesser General Public 
00050  * License LGPL along with this program. 
00051  * If not, see <http://www.gnu.org/licenses/>.
00052  *
00053  ****************************************************************/
00054 
00055 #include "serialIO.h"
00056 #include "sys/select.h"
00057 #include <iostream>
00058 #include <cstring>
00059 
00060 SerialIO::SerialIO() :
00061          _fd(-1)
00062 {
00063 }
00064 
00065 SerialIO::~SerialIO()
00066 {
00067         closePort();
00068 }
00069 
00070 // Open Serial Port
00071 int SerialIO::openPort(std::string devicestring, int baudrate)
00072 {
00073         if(_fd != -1) return _fd;
00074 
00075         speed_t baud = getBaudFromInt(baudrate);
00076         std::memset(&port_settings,0,sizeof(port_settings));
00077         port_settings.c_iflag = 0;
00078         port_settings.c_oflag = 0;
00079         port_settings.c_cflag = CS8|CREAD|CLOCAL;
00080         port_settings.c_lflag = 0;
00081         port_settings.c_cc[VMIN]=1;
00082         port_settings.c_cc[VTIME]=5;
00083 
00084         _fd=open(devicestring.c_str(), O_RDWR | O_NONBLOCK);
00085         cfsetospeed(&port_settings, baud);
00086         cfsetispeed(&port_settings, baud);
00087 
00088         tcsetattr(_fd, TCSANOW, &port_settings);
00089 
00090         return _fd;
00091 }
00092 
00093 // Send Data to Serial Port
00094 int SerialIO::sendData(std::string value)
00095 {
00096         int wrote = -1;
00097         if(_fd != -1)
00098                 wrote = write(_fd, value.c_str(), value.length());
00099         return wrote;
00100 }
00101 
00102 // Send Data to Serial Port
00103 int SerialIO::sendData(const char* data, size_t len)
00104 {
00105         int wrote = -1;
00106         if(_fd != -1)
00107                 wrote = write(_fd, data, len);
00108         return wrote;
00109 }
00110 
00111 // Read Data from Serial Port
00112 int SerialIO::readData(std::string &value, size_t nBytes)
00113 {
00114         fd_set fds;
00115         FD_ZERO(&fds);
00116         FD_SET(_fd, &fds);
00117         struct timeval timeout = {0, 100000};
00118         char buffer[32];
00119         size_t rec = -1;
00120         if(select(_fd+1, &fds, NULL, NULL, &timeout))
00121         {
00122                 rec = read(_fd, buffer, nBytes);
00123                 value = std::string(buffer);
00124         }
00125         
00126         return rec;
00127 }
00128 
00129 // Check if Serial Port is opened
00130 bool SerialIO::isOpen()
00131 {
00132         return (_fd != -1);
00133 }
00134 
00135 // Close Serial Port
00136 void SerialIO::closePort()
00137 {
00138         if(_fd != -1)
00139                 close(_fd);
00140 }
00141 
00142 
00143 speed_t SerialIO::getBaudFromInt(int baud)
00144 {
00145         speed_t ret;
00146         switch(baud)
00147         {
00148                 case 0:         ret=B0;         break;
00149                 case 50:        ret=B50;        break;
00150                 case 75:        ret=B75;        break;
00151                 case 110:       ret=B110;       break;
00152                 case 134:       ret=B134;       break;
00153                 case 150:       ret=B150;       break;
00154                 case 200:       ret=B200;       break;
00155                 case 300:       ret=B300;       break;
00156                 case 1200:      ret=B1200;      break;
00157                 case 1800:      ret=B1800;      break;
00158                 case 2400:      ret=B2400;      break;
00159                 case 4800:      ret=B4800;      break;
00160                 case 9600:      ret=B9600;      break;
00161                 case 19200: ret=B19200; break;
00162                 case 38400: ret=B38400; break;
00163                 case 57600: ret=B57600; break;
00164                 case 115200: ret=B115200; break;
00165                 case 230400: ret=B230400; break;
00166                 default:
00167                         ret=B230400;
00168                         break;
00169         }
00170         return ret;
00171 }


cob_light
Author(s): Benjamin Maidel
autogenerated on Thu Aug 27 2015 12:46:10