thing_reader.h
Go to the documentation of this file.
00001 /* 
00002 Copyright (c) 2017, Brian Bingham
00003 All rights reserved
00004 
00005 This file is part of the thingmagic_rfid package.
00006 
00007 thingmagic_rfid is free software: you can redistribute it and/or modify
00008 it under the terms of the GNU General Public License as published by
00009 the Free Software Foundation, either version 3 of the License, or
00010 (at your option) any later version.
00011 
00012 thingmagic_rfid is distributed in the hope that it will be useful,
00013 but WITHOUT ANY WARRANTY; without even the implied warranty of
00014 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00015 GNU General Public License for more details.
00016 
00017 You should have received a copy of the GNU General Public License
00018 along with the package.  If not, see <http://www.gnu.org/licenses/>.
00019 
00020 */
00021 
00022 
00023 #ifndef _THING_READER_H
00024 #define _THING_READER_H
00025 
00026 #include <cstdio>
00027 #include <unistd.h>
00028 
00029 extern "C"{
00030 #include "tm_reader.h"
00031 }
00032 #include <stdio.h>
00033 #include <stdlib.h>
00034 #include <stdarg.h>
00035 #include <string.h>
00036 #include <inttypes.h>
00037 #include <unistd.h>
00038 
00039 
00040 // ROS
00041 #include "ros/ros.h"
00042 #include "std_msgs/String.h"
00043 
00047 namespace TMR
00048 {
00053   class ThingReader
00054   {
00055   public:
00059     ThingReader();
00060 
00062     ~ThingReader();
00063 
00067     int run();
00068 
00069     void rfid_callback(TMR_Reader *reader, const TMR_TagReadData *t, void *cookie);
00070 
00071   private:
00072     ros::Publisher string_pub_;
00073     std_msgs::String string_msg_;
00074 
00075 
00076  
00077   }; // TMR class
00078 
00079   void errx(int exitval, const char *fmt, ...);
00080   void checkerr(TMR_Reader* rp, TMR_Status ret, int exitval, const char *msg);
00081   void callback_wrapper(TMR_Reader *reader, const TMR_TagReadData *t, void *cookie);
00082   void exceptionCallback(TMR_Reader *reader, TMR_Status error, void *cookie);
00083 
00084 } // namespace TMR
00085 
00086 
00087 
00088 
00089 
00090 
00091 #endif 


thingmagic_rfid
Author(s): Brian Bingham
autogenerated on Thu May 16 2019 03:01:24