Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 __author__ = "astambler@willowgarage.com (Adam Stambler)"
00035
00036 from xbee import XBee
00037 import serial
00038
00039 from rosserial_python import SerialClient
00040 import rospy
00041
00042 import threading
00043 import sys
00044 import time
00045 import struct
00046
00047 client_ports= {}
00048 clients = {}
00049
00050 debug = False;
00051
00052 import threading
00053
00054
00055 class FakeSerial():
00056 def __init__(self, id, xbee):
00057 self.rxdata =''
00058 self.xbee = xbee
00059 self.id = id
00060 self.lock = threading.Lock()
00061 self.timeout = 0.1
00062
00063 def read(self, size = 1):
00064 t= 0
00065 counts = self.timeout/0.01
00066
00067 while( ( len(self.rxdata) < size ) and (not rospy.is_shutdown()) ):
00068 time.sleep(0.01)
00069 t = t +1
00070 if (t > counts):
00071 return ''
00072
00073 with (self.lock):
00074 out = self.rxdata[:size]
00075 self.rxdata = self.rxdata[size:]
00076
00077
00078 return out
00079
00080 def write(self, data):
00081 if (debug):
00082 print "Sending ", [d for d in data]
00083 self.xbee.send('tx', frame_id='0', options="\x01", dest_addr=self.id,data=data)
00084
00085 def putData(self, data):
00086 with (self.lock):
00087 self.rxdata = self.rxdata+data
00088
00089 def flushInput(self):
00090 self.rxdata = ''
00091
00092
00093 if __name__== '__main__':
00094 print "RosSerial Xbee Network"
00095 rospy.init_node('xbee_network')
00096 sys.argv= rospy.myargv(argv=sys.argv)
00097
00098 xbee_port = ''
00099 network_ids = []
00100
00101 if len(sys.argv) <3 :
00102 print """
00103 This program connects to rosserial xbee nodes. The program must be called
00104 like :
00105
00106 ./xbee_network.py <xbee_serial_port> ID1 [ ID2 ID3 ....]
00107 """
00108 exit()
00109 else :
00110 xbee_port = sys.argv[1]
00111 network_ids = [ struct.pack('>h', int(id) ) for id in sys.argv[2:] ]
00112
00113 print "Contacting Xbees : " , network_ids
00114
00115
00116
00117 ser = serial.Serial(xbee_port, 57600, timeout=0.01)
00118 ser.flush()
00119 ser.flushInput()
00120 ser.flushOutput()
00121 time.sleep(1)
00122
00123 xbee = XBee(ser, escaped= True)
00124
00125 for xid in network_ids:
00126 client_ports[xid] = FakeSerial(xid, xbee)
00127 time.sleep(.2)
00128 clients[xid] = SerialClient(client_ports[xid])
00129
00130 threads = [ threading.Thread(target=c.run) for c in clients.values()]
00131
00132 for t in threads:
00133 t.deamon =True
00134 t.start()
00135
00136 while not rospy.is_shutdown():
00137 try:
00138 msg = xbee.wait_read_frame()
00139 if (debug):
00140 print "Received " , msg
00141
00142 if msg['id'] == 'rx':
00143 src = msg['source_addr']
00144 data = msg['rf_data']
00145 try:
00146 client_ports[src].putData(data)
00147 except KeyError as e:
00148 print "Rcv ID corrupted"
00149 except KeyboardInterrupt:
00150 break
00151 ser.close()
00152
00153 print "Quiting the Sensor Network"
00154
00155