embedded_linux_hardware.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 #ifdef __linux__
00047 #include <time.h>
00048 #endif
00049 
00050 // Includes necessary to support time on OS X.
00051 #ifdef __MACH__
00052 #include <mach/mach.h>
00053 #include <mach/mach_time.h>
00054 static mach_timebase_info_data_t    sTimebaseInfo;
00055 #endif
00056 
00057 #define DEFAULT_PORT "/dev/ttyAM1"
00058 
00059 class EmbeddedLinuxHardware
00060 {
00061 public:
00062   EmbeddedLinuxHardware(const char *pn, long baud = 57600)
00063   {
00064     strncpy(portName, pn, 30);
00065     baud_ = baud;
00066   }
00067 
00068   EmbeddedLinuxHardware()
00069   {
00070     const char *envPortName = getenv("ROSSERIAL_PORT");
00071     if (envPortName == NULL)
00072       strcpy(portName, DEFAULT_PORT);
00073     else
00074       strncpy(portName, envPortName, 29);
00075     portName[29] = '\0'; // in case user gave us too long a port name
00076     baud_ = 57600;
00077   }
00078 
00079   void setBaud(long baud)
00080   {
00081     this->baud_ = baud;
00082   }
00083 
00084   int getBaud()
00085   {
00086     return baud_;
00087   }
00088 
00089   void init()
00090   {
00091     fd = elCommInit(portName, baud_);
00092     if (fd < 0)
00093     {
00094       std::cout << "Exiting" << std::endl;
00095       exit(-1);
00096     }
00097     std::cout << "EmbeddedHardware.h: opened serial port successfully\n";
00098 
00099     initTime();
00100   }
00101 
00102   void init(const char *pName)
00103   {
00104     fd = elCommInit(pName, baud_);
00105     if (fd < 0)
00106     {
00107       std::cout << "Exiting" << std::endl;
00108       exit(-1);
00109     }
00110     std::cout << "EmbeddedHardware.h: opened comm port successfully\n";
00111 
00112     initTime();
00113   }
00114 
00115   int read()
00116   {
00117     int c = elCommRead(fd);
00118     return c;
00119   }
00120 
00121   void write(uint8_t* data, int length)
00122   {
00123     elCommWrite(fd, data, length);
00124   }
00125 
00126 #ifdef __linux__
00127   void initTime()
00128   {
00129     clock_gettime(CLOCK_MONOTONIC, &start);
00130   }
00131 
00132   unsigned long time()
00133   {
00134     struct timespec end;
00135     long seconds, nseconds;
00136 
00137     clock_gettime(CLOCK_MONOTONIC, &end);
00138 
00139     seconds  = end.tv_sec  - start.tv_sec;
00140     nseconds = end.tv_nsec - start.tv_nsec;
00141 
00142     return ((seconds) * 1000 + nseconds / 1000000.0) + 0.5;
00143   }
00144 
00145 #elif __MACH__
00146   void initTime()
00147   {
00148     start = mach_absolute_time();
00149     mach_timebase_info(&sTimebaseInfo);
00150   }
00151 
00152   unsigned long time()
00153   {
00154     // See: https://developer.apple.com/library/mac/qa/qa1398/_index.html
00155     uint64_t elapsed = mach_absolute_time() - start;
00156     return elapsed * sTimebaseInfo.numer / (sTimebaseInfo.denom * 1000000);
00157   }
00158 #endif
00159 
00160 protected:
00161   int fd;
00162   char portName[30];
00163   long baud_;
00164 
00165 #ifdef __linux__
00166   struct timespec start;
00167 #elif __MACH__
00168   uint64_t start;
00169 #endif
00170 };
00171 
00172 #endif


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Sat Oct 7 2017 03:08:43