7 from thingmagic_usbpro.msg
import RFID_Detection
11 RFID_Detection message format: 21 |_ _| |__ (_)_ __ __ _| \/ | __ _ __ _(_) ___ 22 | | | '_ \| | '_ \ / _` | |\/| |/ _` |/ _` | |/ __| 23 | | | | | | | | | | (_| | | | | (_| | (_| | | (__ 24 |_| |_| |_|_|_| |_|\__, |_| |_|\__,_|\__, |_|\___| 26 _ _ ____ ____ ____ _____ ___ ____ 27 | | | / ___|| __ ) _ __ _ __ ___ | _ \| ___|_ _| _ \ 28 | | | \___ \| _ \| '_ \| '__/ _ \ | |_) | |_ | || | | | 29 | |_| |___) | |_) | |_) | | | (_) | | _ <| _| | || |_| | 30 \___/|____/|____/| .__/|_| \___/ |_| \_\_| |___|____/ 33 | _ \ ___ __ _ __| | ___ _ __ 34 | |_) / _ \/ _` |/ _` |/ _ \ '__| 35 | _ < __/ (_| | (_| | __/ | 36 |_| \_\___|\__,_|\__,_|\___|_| 42 pub = rospy.Publisher(
'RFID_detections', RFID_Detection, queue_size=10)
43 rospy.init_node(
'RFID_node', anonymous=
True)
46 port_param = rospy.get_param(
'/rfid_detector_node/port',
'/dev/ttyACM0')
47 region_param = rospy.get_param(
'/rfid_detector_node/region',
'NA')
48 rate_param = rospy.get_param(
'/rfid_detector_node/rate', 10)
51 rospy.loginfo(
"Got port name param: "+port_param)
52 rospy.loginfo(
"Got region param: "+region_param)
53 rospy.loginfo(
"Got publishing rate param: "+str(rate_param))
56 reader = mercury.Reader(
"tmr://" + port_param)
57 except Exception
as e:
58 rospy.loginfo(
"Couldn't open RFID reader on port: "+str(port_param))
59 raise rospy.exceptions.ROSInitException(
"couldn't open port for RFID reader, check Launch file for port name")
63 reader.set_region(region_param)
64 except Exception
as e:
65 rospy.loginfo(
"Couldn't set RFID reader's region to: "+str(region_param))
66 raise rospy.exceptions.ROSInitException(
"couldn't set region for RFID reader")
69 rate = rospy.Rate(int(rate_param))
71 while not rospy.is_shutdown():
72 result = reader.read(5)
73 for tagdata
in result:
74 rospy.loginfo(
"Antenna:%i Read_Count:%i RSSI:%i EPC:%s" %(tagdata.antenna, tagdata.read_count,tagdata.rssi,tagdata.epc))
75 detect_msg = RFID_Detection(str(tagdata.epc),tagdata.antenna,tagdata.read_count,tagdata.rssi)
76 pub.publish(detect_msg)
79 if __name__ ==
'__main__':
82 except rospy.ROSInterruptException:
def RFID_Topic_Publisher()