tm_usbpro.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 ## Grabs RFID detection data from the ThingMagic USBPro RFID reader and publishes
00004 ## thingmagic_usbpro/RFID_Detection messages to the RFID_detections
00005 
00006 import rospy
00007 from thingmagic_usbpro.msg import RFID_Detection
00008 import mercury
00009 
00010 '''
00011 RFID_Detection message format:
00012 string epc
00013 int8 antenna
00014 int8 read_count
00015 int8 rssi
00016 '''
00017 
00018 
00019 banner='''
00020  _____ _     _             __  __             _      
00021 |_   _| |__ (_)_ __   __ _|  \/  | __ _  __ _(_) ___ 
00022   | | | '_ \| | '_ \ / _` | |\/| |/ _` |/ _` | |/ __|
00023   | | | | | | | | | | (_| | |  | | (_| | (_| | | (__ 
00024   |_| |_| |_|_|_| |_|\__, |_|  |_|\__,_|\__, |_|\___|
00025                      |___/              |___/        
00026  _   _ ____  ____                    ____  _____ ___ ____  
00027 | | | / ___|| __ ) _ __  _ __ ___   |  _ \|  ___|_ _|  _ \ 
00028 | | | \___ \|  _ \| '_ \| '__/ _ \  | |_) | |_   | || | | |
00029 | |_| |___) | |_) | |_) | | | (_) | |  _ <|  _|  | || |_| |
00030  \___/|____/|____/| .__/|_|  \___/  |_| \_\_|   |___|____/ 
00031                   |_|                                      
00032  ____                _           
00033 |  _ \ ___  __ _  __| | ___ _ __ 
00034 | |_) / _ \/ _` |/ _` |/ _ \ '__|
00035 |  _ <  __/ (_| | (_| |  __/ |   
00036 |_| \_\___|\__,_|\__,_|\___|_|
00037 '''
00038 
00039 
00040 def RFID_Topic_Publisher():
00041 
00042     pub = rospy.Publisher('RFID_detections', RFID_Detection, queue_size=10)
00043     rospy.init_node('RFID_node', anonymous=True)
00044     rospy.loginfo(banner)   
00045 
00046     port_param = rospy.get_param('/rfid_detector_node/port', '/dev/ttyACM0')
00047     region_param = rospy.get_param('/rfid_detector_node/region', 'NA')
00048     rate_param = rospy.get_param('/rfid_detector_node/rate', 10)
00049 
00050 
00051     rospy.loginfo("Got port name param: "+port_param)
00052     rospy.loginfo("Got region param: "+region_param)
00053     rospy.loginfo("Got publishing rate param: "+str(rate_param))
00054 
00055     try:
00056         reader = mercury.Reader("tmr://" + port_param)
00057     except Exception as e:
00058         rospy.loginfo("Couldn't open RFID reader on port: "+str(port_param))
00059         raise rospy.exceptions.ROSInitException("couldn't open port for RFID reader, check Launch file for port name")
00060         quit(1)
00061 
00062     try:
00063         reader.set_region(region_param)
00064     except Exception as e: 
00065         rospy.loginfo("Couldn't set RFID reader's region to: "+str(region_param))
00066         raise rospy.exceptions.ROSInitException("couldn't set region for RFID reader")
00067         quit(1)
00068 
00069     rate = rospy.Rate(int(rate_param)) #hz
00070 
00071     while not rospy.is_shutdown():
00072         result = reader.read(5)
00073         for tagdata in result:
00074             rospy.loginfo("Antenna:%i Read_Count:%i RSSI:%i EPC:%s" %(tagdata.antenna, tagdata.read_count,tagdata.rssi,tagdata.epc))
00075             detect_msg = RFID_Detection(str(tagdata.epc),tagdata.antenna,tagdata.read_count,tagdata.rssi)
00076             pub.publish(detect_msg)
00077         rate.sleep()
00078 
00079 if __name__ == '__main__':
00080     try:
00081         RFID_Topic_Publisher()
00082     except rospy.ROSInterruptException:
00083         pass
00084 


thingmagic_usbpro
Author(s):
autogenerated on Sun Apr 16 2017 02:28:06