The Real Time Socket Template comes in two parts, the socket sensor base and the data parser / publisher. The sensor base is a generic socket client that takes in a name, an address, and a polling timer and calls parse once it receives a carriage return and a newline. ("\r\n")
#!/usr/bin/python
import threading
import socket
import time
class SocketSensorBase(threading.Thread):
def __init__(self,threadName,refreshTimer,address,port,timeout):
threading.Thread.__init__(self, name = threadName)
self.__running = False
self.__shutdown = False
self.__refreshTimer = refreshTimer
self.__lostConnectionRefreshTimer = 5
self.__socketTimout = timeout
self.__connected = False
self.__file = "";
self.__failedReadAttempts = 0;
self.__failedReadAttemptLimit = 10;
self.__address = address;
self.__port = port;
print threadName + " logger started"
self.setAndConnect(self.__address,self.__port)
def getSocket(self):
return self.__sock
def getFile(self):
return self.__file
def resetAndConnect(self):
self.__sock.shutdown(socket.SHUT_RDWR)
self.__sock.close()
self.setAndConnect(self.__address,self.__port)
def setAndConnect(self,address,port):
try:
self.__sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.__sock.settimeout(self.__socketTimout)
self.__sock.connect((address, port))
self.__file = self.__sock.makefile("rb")
self.__connected = True
except socket.error, e:
print e
def run(self):
self.__running = True
while not self.__shutdown:
if self.__connected:
self.processData()
if self.__refreshTimer != 0:
time.sleep(self.__refreshTimer)
else:
time.sleep(self.__lostConnectionRefreshTimer)
self.setAndConnect(self.__address,self.__port)
self.__shutdown = False
self.__running = False
def processData(self):
rawData = self.read()
if rawData:
self.parse(rawData)
else:
self.__failedReadAttempts += 1
if(self.__failedReadAttempts >= self.__failedReadAttemptLimit):
self.__failedReadAttempts = 0;
self.__connected = False;
def read(self):
try:
s = self.__file.readline()
if not s:
return s
if s[-2:] == '\r\n':
s = s[:-2]
elif s[-1:] in '\r\n':
s = s[:-1]
return s
except:
return
def parse(self,rawData):
print "override me"
def shutdown(self):
self.__shutdown = True
self.__running = False
The example AirRobot data parser / publisher overrides the parse method and publishes the incoming data to the ROS blackboard.
#!/usr/bin/python
import rospy
import time
import re
from socketSensorBase import SocketSensorBase
from airRobot_logger.msg import battery
class BatteryLogger(SocketSensorBase):
def __init__(self):
#set the name of the thread, the refresh timer and the address
super(BatteryLogger, self).__init__("battery",.05,'10.0.1.5',3000,20) #SET IP ADDRESS
#create the ROS publisher and msgs
self.__pub_battery = rospy.Publisher('airrobot_battery', battery)
self.__batteryMsg = battery()
print "battery logger started"
"""
logs Air Robot Battery Data
"""
def parse(self,data):
try:
#print data
data = data.split(",")
#"looking for [battery,flags,voltage,level]"
if(data[0] == 'battery'):
self.__batteryMsg.header.stamp = rospy.get_rostime()
self.__batteryMsg.name = data[0]
self.__batteryMsg.flags = data[1]
self.__batteryMsg.voltage = float(data[2])
self.__batteryMsg.level = int(data[3])
if not rospy.is_shutdown():
self.__pub_battery.publish(self.__batteryMsg)
else:
print "Not Logged: " + data[0]
except Exception as e:
print e
return
def start():
batteryLogger = BatteryLogger()
batteryLogger.start()
if __name__ == "__main__":
rospy.init_node('airrobot_battery_logger')
start()