21 pub = {
"op":
"publish",
"topic": topic,
"msg": obj}
24 def subscribe(self, topic, callback, throttle_rate=-1):
26 sub = {
"op":
"subscribe",
"topic": topic}
28 sub[
'throttle_rate'] = throttle_rate
33 keys_for_deletion = []
34 for key, values
in self.callbacks.iteritems():
40 keys_for_deletion.append(key)
42 for key
in keys_for_deletion:
44 self.callbacks.pop(key)
47 unsub = {
"op":
"unsubscribe",
"topic": topic}
52 call = {
"op":
"call_service",
"id": id,
"service": serviceName}
65 while self.
resp ==
None:
76 self.connection.sendString(json.dumps(obj))
82 return ''.join(random.SystemRandom().choice(string.ascii_letters + string.digits)
for _
in range(chars))
88 if self.callbacks.has_key(topic):
96 return self.connection.connected
99 return self.connection.errored
104 obj = json.loads(message)
107 if obj.has_key(
'op'):
109 if option ==
"publish":
112 if self.callbacks.has_key(topic):
117 print "exception on callback", callback,
"from", topic
118 traceback.print_exc()
120 elif option ==
"service_response":
121 if obj.has_key(
"id"):
123 values = obj[
"values"]
124 if self.service_callbacks.has_key(id):
129 print "exception on callback ID:", id
130 traceback.print_exc()
135 print "Recieved unknown option - it was: ", option
139 print "exception in onMessageReceived" 140 print "message", message
141 traceback.print_exc()
155 print "### ROS bridge connected ###" 160 print "Error: not connected, could not send message" 163 self.ws.send(message)
167 print "Error: %s" % error
171 print "### ROS bridge closed ###" 174 self.ws.run_forever()
182 self.callbacks.append(callback)
def unhook(self, callback)
def onMessageReceived(self, message)
def addServiceCallback(self, id, callback)
def subscribe(self, topic, callback, throttle_rate=-1)
def registerCallback(self, callback)
def addCallback(self, topic, callback)
def on_message(self, ws, message)
def sendString(self, message)
def generate_id(self, chars=16)
def __init__(self, host, port)
def unsubscribe(self, topic)
def callback(self, msg_dict)
doesn't work: once ubsubscribed, robot doesn't let us subscribe again if self.pub.get_num_connections() == 0: rospy.loginfo("[%s] stopping to stream messages on topic '%s'", rospy.get_name(), self.topic_config.topic) self.robot.unsubscribe(topic=('/' + self.topic_config.topic))
def __init__(self, host, port)
def publish(self, topic, obj)
def on_error(self, ws, error)
def callService(self, serviceName, callback=None, msg=None)