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
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044 import rospy
00045
00046
00047 import applanix_generated_msgs.srv
00048 import applanix_msgs.msg
00049
00050
00051 from port import Port
00052 from handlers import AckHandler
00053 import mapping
00054
00055
00056 import threading
00057 from cStringIO import StringIO
00058
00059
00060 SILENCE_INTERVAL=5.0
00061
00062
00063 class ControlPort(Port):
00064 def run(self):
00065 self.sock.setblocking(1)
00066 self.services_ready = threading.Event()
00067 self.services = []
00068 self.lock = threading.Lock()
00069 self.last_transaction_number = 0
00070
00071 for msg_num in mapping.msgs.keys():
00072 if msg_num != 0:
00073 self.services.append(ServiceHandler(msg_num, self))
00074 self.services_ready.set()
00075
00076
00077
00078 set_nav_mode = rospy.ServiceProxy("nav_mode", applanix_generated_msgs.srv.NavModeControl)
00079 nav_mode_msg = applanix_msgs.msg.NavModeControl(mode=applanix_msgs.msg.NavModeControl.MODE_NAVIGATE)
00080 while not self.finish.is_set():
00081 rospy.sleep(SILENCE_INTERVAL)
00082 set_nav_mode(nav_mode_msg)
00083
00084 def next_transaction(self):
00085 self.last_transaction_number += 1
00086 return self.last_transaction_number
00087
00088
00089 class ServiceHandler(object):
00090 def __init__(self, msg_num, port):
00091 self.name, data_class = mapping.msgs[msg_num]
00092 self.port = port
00093 self.service = rospy.Service(self.name, getattr(applanix_generated_msgs.srv, data_class.__name__), self.handle)
00094
00095
00096 self.header = applanix_msgs.msg.CommonHeader(start=applanix_msgs.msg.CommonHeader.START_MESSAGE, id=msg_num, length=0)
00097
00098 def handle(self, message):
00099
00100
00101
00102 with self.port.lock:
00103
00104 message.request.transaction = self.port.next_transaction()
00105 self.port.send(self.header, message.request)
00106
00107
00108 pkt_id, pkt_str = self.port.recv()
00109
00110 if pkt_id == None:
00111 raise ValueError("No response message on control port.")
00112
00113 if pkt_id != (applanix_msgs.msg.CommonHeader.START_MESSAGE, 0):
00114 raise ValueError("Non-ack message on control port: %s.%d" % pkt_id)
00115
00116 handler = AckHandler()
00117 handler.handle(StringIO(pkt_str))
00118
00119 return handler.message