def refresh(self): ''' Refreshes the optical flow reading. ''' self._refreshed = True # Grab bytes from the device bytes = self.dev.read(_BUFSIZE) # Check for MAVLINK messages in bytes MAVLinkParser.process(self, bytes)
def __init__(self, port): ''' Creates a new PX4Flow object on the specified port. ''' # Baud rate is unspecified self.dev = serial.Serial(port) # Create MAVLink object for parsing MAVLinkParser.__init__(self, self, MSG_OPTICAL_FLOW) # Require refresh before first reading self._refreshed = False
def getQuality(self): ''' Returns quality in percent. ''' self._check_refreshed() return MAVLinkParser.unpack_uint8(self, 25)
def getGroundDistance(self): ''' Returns ground distance (height) in meters. ''' self._check_refreshed() return MAVLinkParser.unpack1(self, 'f', 16, 20)
def getFlowComp(self): ''' Returns computed X,Y in meters. ''' self._check_refreshed() return MAVLinkParser.unpack(self, 'ff', 8, 16, 2)
def getFlow(self): ''' Returns raw sensor X,Y. ''' self._check_refreshed() return MAVLinkParser.unpack(self, 'hh', 20, 24, 2)
def getTime(self): ''' Returns current time in microseconds. ''' self._check_refreshed() return MAVLinkParser.unpack1(self, 'Q', 0, 8)