EmbeddedLinuxHardware.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, Willow Garage, Inc.
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions
00009  * are met:
00010  *
00011  *  * Redistributions of source code must retain the above copyright
00012  *    notice, this list of conditions and the following disclaimer.
00013  *  * Redistributions in binary form must reproduce the above
00014  *    copyright notice, this list of conditions and the following
00015  *    disclaimer in the documentation and/or other materials provided
00016  *    with the distribution.
00017  *  * Neither the name of Willow Garage, Inc. nor the names of its
00018  *    contributors may be used to endorse or promote prducts derived
00019  *    from this software without specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  * POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #ifndef ROS_EMBEDDED_LINUX_HARDWARE_H_
00036 #define ROS_EMBEDDED_LINUX_HARDWARE_H_
00037 
00038 #include <iostream>
00039 
00040 #ifdef BUILD_LIBROSSERIALEMBEDDEDLINUX
00041 extern "C" int elCommInit(char *portName, int baud);
00042 extern "C" int elCommRead(int fd);
00043 extern "C" elCommWrite(int fd, uint8_t* data, int length);
00044 #endif
00045 
00046 #define DEFAULT_PORT "/dev/ttyAM1"
00047 
00048 class EmbeddedLinuxHardware {
00049   public:
00050     EmbeddedLinuxHardware(char *pn, long baud= 57600){
00051       strncpy(portName, pn, 30);
00052       baud_ = baud;
00053     }
00054     EmbeddedLinuxHardware()
00055     {
00056       char *envPortName = getenv("ROSSERIAL_PORT");
00057       if (envPortName == NULL)
00058         strcpy(portName, DEFAULT_PORT);
00059       else
00060         strncpy(portName, envPortName, 29);
00061       portName[29] = '\0'; // in case user gave us too long a port name
00062       baud_ = 57600;
00063     }
00064 
00065     void setBaud(long baud){
00066       this->baud_= baud;
00067     }
00068 
00069     int getBaud(){return baud_;}
00070 
00071     void init(){
00072         fd = elCommInit(portName, baud_);
00073         if (fd < 0) {
00074                 std::cout << "Exiting" << std::endl;
00075                 exit(-1);
00076         }
00077         std::cout << "EmbeddedHardware.h: opened serial port successfully\n";
00078         clock_gettime(CLOCK_MONOTONIC, &start);                 // record when the program started
00079     }
00080 
00081     void init(char *pName){
00082         fd = elCommInit(pName, baud_);
00083         if (fd < 0) {
00084                 std::cout << "Exiting" << std::endl;
00085                 exit(-1);
00086         }
00087         std::cout << "EmbeddedHardware.h: opened comm port successfully\n";
00088         clock_gettime(CLOCK_MONOTONIC, &start);                 // record when the program started
00089     }
00090 
00091     int read()
00092     {
00093         int c = elCommRead(fd);
00094                 //std::cout << "read() got: " << c << std::endl;
00095         if (c > 0) {
00096         }
00097         return c;
00098     }
00099 
00100     void write(uint8_t* data, int length)
00101     {
00102       elCommWrite(fd, data, length);
00103 //      for (int i=0; i<length; i++) {
00104 //        std::cout <<  "i:" << i << " data: " << data[i];
00105 //      }
00106 //      std::cout << std::endl;
00107     }
00108 
00109     unsigned long time()
00110     {
00111         long millis, seconds, nseconds;
00112 
00113         clock_gettime(CLOCK_MONOTONIC, &end);
00114 
00115         seconds  = end.tv_sec  - start.tv_sec;
00116         nseconds = end.tv_nsec - start.tv_nsec;
00117 
00118         millis = ((seconds) * 1000 + nseconds/1000000.0) + 0.5;
00119 
00120         return millis;
00121     }
00122 
00123   protected:
00124     int fd;
00125     char portName[30];
00126     long baud_;
00127     struct timespec start, end;
00128 };
00129 
00130 #endif


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Fri Dec 6 2013 20:35:58