def __init__(self): event.EventLoop.__init__(self) AI.Detector.__init__(self) self.load_pipeline(self.options.Pipeline_Name) self.node.subMessage(messaging.CirclesMessage()) self.node.addObserver(self) self.log('Looking for the buoy') self.circles = deque(maxlen=self.options.Max_Samples) self.times = deque(maxlen=self.options.Max_Samples)
def __init__(self): event.EventLoop.__init__(self) AI.Script.__init__(self) self.load_pipeline(self.options.Pipeline_Name) self.node.subMessage(msg.CirclesMessage()) self.node.addObserver(self) self.log('Looking for the buoy') self.circles = deque(maxlen = self.options.Max_Samples) self.times = deque(maxlen = self.options.Max_Samples) self.foundBuoy = False if self.options.useDepth: self.auv.depth(self.options.depth) self.auv.bearingAndWait(self.options.initialBearing) print('Prepping to go to subMessage') self.node.subMessage(msg.LinesMessage()) print('Past submessage') self.found = False
def run(self): self.load_pipeline('detect_buoy_sim') self.time_last_seen = None #get initial bearing if self.auv.current_bearing == None: time.sleep(1) if self.auv.current_bearing == None: error("No bearing information, giving up.") raise Exception("No bearing information.") start_bearing = self.auv.current_bearing total_right_angles_turned = 0 last_bearing = self.auv.current_bearing #start circle processing info('Waiting for circles...') self.node.subMessage(msg.CirclesMessage()) #monitor progress while total_right_angles_turned < self.options.TotalRightAnglesToTurn: time.sleep(min(self.options.Do_Prop_Time, self.options.Warn_Seconds_Between_Sights)/2.) time_since_seen = 0 if self.time_last_seen is None: warning('Not seen buoy, waiting') else: time_since_seen = time.time() - self.time_last_seen if time_since_seen > self.options.Do_Prop_Time: self.auv.prop(0) if time_since_seen > self.options.Warn_Seconds_Between_Sights: warning('cannot see buoy: last seen %g seconds ago' % time_since_seen) self.auv.strafe(0) self.auv.prop(0) if time_since_seen > self.options.Give_Up_Seconds_Between_Sights: self.log('Buoy Circling: lost sight of the buoy!') return False #note travelling left, so turning clockwise ie bearing increasing if (self.auv.current_bearing != None): bearing_diff = abs(self.auv.current_bearing - last_bearing) if min(bearing_diff, 360-bearing_diff) > 90: #assume we don't turn to fast last_bearing = (last_bearing+90)%360 total_right_angles_turned += 1 self.auv.stop() self.log('Buoy Circling: completed successfully') return
+ r).streamline() p_PipelineDiscoveryRequestMessage.setParseAction(lambda x: messaging.PipelineDiscoveryRequestMessage(*x[0])) p_PipelineDiscoveryResponseMessage = pp.Group(l \ + p_str \ + r).streamline() p_PipelineDiscoveryResponseMessage.setParseAction(lambda x: messaging.PipelineDiscoveryResponseMessage(*x[0])) p_LinesMessage = pp.Group(l \ + p_str + c \ + p_LineVec \ + r).streamline() p_LinesMessage.setParseAction(lambda x: messaging.LinesMessage(*x[0])) p_CirclesMessage = pp.Group(l \ + p_str + c \ + p_CircleVec \ + r).streamline() p_CirclesMessage.setParseAction(lambda x: messaging.CirclesMessage(*x[0])) p_CornersMessage = pp.Group(l \ + p_str + c \ + p_CornerVec \ + r).streamline() p_CornersMessage.setParseAction(lambda x: messaging.CornersMessage(*x[0])) p_KeyPointsMessage = pp.Group(l \ + p_str + c \ + p_KeyPointVec \ + r).streamline() p_KeyPointsMessage.setParseAction(lambda x: messaging.KeyPointsMessage(*x[0])) p_HistogramMessage = pp.Group(l \ + p_str + c \ + p_floatVec \ + r).streamline() p_HistogramMessage.setParseAction(lambda x: messaging.HistogramMessage(*x[0]))