Beispiel #1
0
    def update_sensors(self, data_type, buffer_id, sequence_number, raw_data,
                       ack):
        """
        Update the sensors (called via the wifi or ble connection)

        :param data: raw data packet that needs to be parsed
        :param ack: True if this packet needs to be ack'd and False otherwise
        """
        #print("data type is %d buffer id is %d sequence number is %d " % (data_type, buffer_id, sequence_number))
        sensor_list = self.sensor_parser.extract_sensor_values(raw_data)
        #print(sensor_list)
        if (sensor_list is not None):
            for sensor in sensor_list:
                (sensor_name, sensor_value, sensor_enum, header_tuple) = sensor
                if (sensor_name is not None):
                    self.sensors.update(sensor_name, sensor_value, sensor_enum)
                else:
                    color_print(
                        "data type %d buffer id %d sequence number %d" %
                        (data_type, buffer_id, sequence_number), "WARN")
                    color_print(
                        "This sensor is missing (likely because we don't need it)",
                        "WARN")

        if (ack):
            self.drone_connection.ack_packet(buffer_id, sequence_number)
Beispiel #2
0
    def handleNotification(self, cHandle, data):
        #print "handling notificiation from channel %d" % cHandle
        #print "handle map is %s " % self.handle_map[cHandle]
        #print "channel map is %s " % self.mambo.characteristic_receive_uuids[self.handle_map[cHandle]]
        #print "data is %s " % data

        channel = self.ble_connection.characteristic_receive_uuids[self.handle_map[cHandle]]

        (packet_type, packet_seq_num) = struct.unpack('<BB', data[0:2])
        raw_data = data[2:]

        if channel == 'ACK_DRONE_DATA':
            # data received from drone (needs to be ack on 1e)
            #color_print("calling update sensors ack true", "WARN")
            self.mambo.update_sensors(packet_type, None, packet_seq_num, raw_data, ack=True)
        elif channel == 'NO_ACK_DRONE_DATA':
            # data from drone (including battery and others), no ack
            #color_print("drone data - no ack needed")
            self.mambo.update_sensors(packet_type, None, packet_seq_num, raw_data, ack=False)
        elif channel == 'ACK_COMMAND_SENT':
            # ack 0b channel, SEND_WITH_ACK
            #color_print("Ack!  command received!")
            self.ble_connection._set_command_received('SEND_WITH_ACK', True)
        elif channel == 'ACK_HIGH_PRIORITY':
            # ack 0c channel, SEND_HIGH_PRIORITY
            #color_print("Ack!  high priority received")
            self.ble_connection._set_command_received('SEND_HIGH_PRIORITY', True)
        else:
            color_print("unknown channel %s sending data " % channel, "ERROR")
            color_print(cHandle)
Beispiel #3
0
    def handle_frame(self, packet_type, buffer_id, packet_seq_id, recv_data):
        if (buffer_id == self.buffer_ids['PING']):
            #color_print("this is a ping!  need to pong", "INFO")
            self._send_pong(recv_data)

        if (self.data_types_by_number[packet_type] == 'ACK'):
            #print("setting command received to true")
            ack_seq = int(struct.unpack("<B", recv_data)[0])
            self._set_command_received('SEND_WITH_ACK', True, ack_seq)
            self.ack_packet(buffer_id, ack_seq)
        elif (self.data_types_by_number[packet_type] == 'DATA_NO_ACK'):
            #print("DATA NO ACK")
            if (buffer_id in self.data_buffers):
                self.drone.update_sensors(packet_type,
                                          buffer_id,
                                          packet_seq_id,
                                          recv_data,
                                          ack=False)
        elif (self.data_types_by_number[packet_type] == 'LOW_LATENCY_DATA'):
            print("Need to handle Low latency data")
        elif (self.data_types_by_number[packet_type] == 'DATA_WITH_ACK'):
            #print("DATA WITH ACK")
            if (buffer_id in self.data_buffers):
                self.drone.update_sensors(packet_type,
                                          buffer_id,
                                          packet_seq_id,
                                          recv_data,
                                          ack=True)
        else:
            color_print("HELP ME", "ERROR")
            print("got a different type of data - help")
Beispiel #4
0
    def _listen_socket(self):
        """
        Listens to the socket and sleeps in between receives.
        Runs forever (until disconnect is called)
        """

        print("starting listening at ")
        lasttime = time.time()
        data = None

        while (self.is_listening):
            lasttime = time.time()
            try:
                (data, address) = self.udp_receive_sock.recvfrom(66000)

            except socket.timeout:
                print("timeout - trying again")

            except:
                pass

            self.handle_data(data)

        color_print("disconnecting", "INFO")
        self.disconnect()
Beispiel #5
0
    def send_enum_command_packet_ack(self,
                                     command_tuple,
                                     enum_value,
                                     usb_id=None):
        """
        Send a command on the ack channel with enum parameters as well (most likely a flip).
        All commandsandsensors except PCMD go on the ack channel per
        http://forum.developer.parrot.com/t/ble-characteristics-of-minidrones/5912/2

        the id of the last command sent (for use in ack) is the send counter (which is incremented before sending)

        :param command_tuple: 3 tuple of the command bytes.  0 padded for 4th byte
        :param enum_value: the enum index
        :return: nothing
        """
        self.characteristic_send_counter['SEND_WITH_ACK'] = (
            self.characteristic_send_counter['SEND_WITH_ACK'] + 1) % 256
        if (usb_id is None):
            packet = struct.pack(
                "<BBBBBBI", self.data_types['DATA_WITH_ACK'],
                self.characteristic_send_counter['SEND_WITH_ACK'],
                command_tuple[0], command_tuple[1], command_tuple[2], 0,
                enum_value)
        else:
            color_print((self.data_types['DATA_WITH_ACK'],
                         self.characteristic_send_counter['SEND_WITH_ACK'],
                         command_tuple[0], command_tuple[1], command_tuple[2],
                         0, usb_id, enum_value), 1)
            packet = struct.pack(
                "<BBBBHBI", self.data_types['DATA_WITH_ACK'],
                self.characteristic_send_counter['SEND_WITH_ACK'],
                command_tuple[0], command_tuple[1], command_tuple[2], usb_id,
                enum_value)
        return self.send_command_packet_ack(packet)
Beispiel #6
0
    def smart_sleep(self, timeout):
        """
        Sleeps the requested number of seconds but wakes up for notifications

        Note: NEVER use regular time.sleep!  It is a blocking sleep and it will likely
        cause the BLE to disconnect due to dropped notifications.  Always use smart_sleep instead!

        :param timeout: number of seconds to sleep
        :return:
        """

        start_time = datetime.now()
        new_time = datetime.now()
        diff = (new_time - start_time).seconds + \
            ((new_time - start_time).microseconds / 1000000.0)

        while (diff < timeout):
            try:
                notify = self.drone_connection.waitForNotifications(0.1)
            except:
                color_print("reconnecting to wait", "INFO")
                self._reconnect(3)

            new_time = datetime.now()
            diff = (new_time - start_time).seconds + \
                ((new_time - start_time).microseconds / 1000000.0)
Beispiel #7
0
    def __init__(self, address="", use_wifi=False):
        """
        If you need BLE: Initialize with its BLE address - if you don't know the address, call findMambo
        and that will discover it for you.
        You can also connect to the wifi on the FPV camera.  Do not use this if the camera is not connected.  Also,
        ensure you have connected your machine to the wifi on the camera before attempting this or it will not work.
        :param address: unique address for this mambo (can be ignored if you are using wifi)
        :param use_wifi: set to True to connect with wifi instead of BLE
        """
        self.address = address
        self.use_wifi = use_wifi
        self.groundcam = None
        if (use_wifi):
            self.drone_connection = WifiConnection(self, drone_type="Mambo")
            # initialize groundcam
            self.groundcam = MamboGroundcam()
        else:
            if (BLEAvailable):
                self.drone_connection = BLEConnection(address, self)
            else:
                self.drone_connection = None
                color_print(
                    "ERROR: you are trying to use a BLE connection on a system that doesn't have BLE installed.",
                    "ERROR")
                return

        # intialize the command parser
        self.command_parser = DroneCommandParser()

        # initialize the sensors and the parser
        self.sensors = MinidroneSensors()
        self.sensor_parser = DroneSensorParser(drone_type="Minidrone")
Beispiel #8
0
def disconnect():
    print("DONE - disconnecting")
    bebop.stop_video_stream()
    bebop.smart_sleep(5)
    print(bebop.sensors.battery, "% battery left")
    print("Status: ", bebop.sensors.flying_state)
    bebop.disconnect()
    color_print("Disconnected from the drone successfully", "SUCCESS")
Beispiel #9
0
    def send_command_packet_noack(self, packet):
        """
        Sends the actual packet on the No-ack channel.  Internal function only.

        :param packet: packet constructed according to the command rules (variable size, constructed elsewhere)
        :return: True if the command was sent and False otherwise
        """
        try_num = 0
        color_print("sending packet on try %d", try_num)
        self.safe_send(packet)
Beispiel #10
0
    def _perform_handshake(self):
        """
        Magic handshake
        Need to register for notifications and write 0100 to the right handles
        This is sort of magic (not in the docs!) but it shows up on the forum here
        http://forum.developer.parrot.com/t/minimal-ble-commandsandsensors-to-send-for-take-off/1686/2

        :return: nothing
        """
        color_print("magic handshake to make the drone listen to our commandsandsensors")

        # Note this code snippet below more or less came from the python example posted to that forum (I adapted it to my interface)
        for c in self.handshake_characteristics.values():
            # for some reason bluepy characteristic handle is two lower than what I need...
            # Need to write 0x0100 to the characteristics value handle (which is 2 higher)
            self.drone_connection.writeCharacteristic(c.handle + 2, struct.pack("<BB", 1, 0))
Beispiel #11
0
    def send_command_packet_ack(self, packet, seq_id):
        """
        Sends the actual packet on the ack channel.  Internal function only.

        :param packet: packet constructed according to the command rules (variable size, constructed elsewhere)
        :return: True if the command was sent and False otherwise
        """
        try_num = 0
        self._set_command_received('SEND_WITH_ACK', False, seq_id)
        while (try_num < self.max_packet_retries and not self._is_command_received('SEND_WITH_ACK', seq_id)):
            color_print("sending packet on try %d", try_num)
            self.safe_send(packet)
            try_num += 1
            self.smart_sleep(0.5)

        return self._is_command_received('SEND_WITH_ACK', seq_id)
Beispiel #12
0
    def safe_land(self, timeout):
        """
        Ensure the mambo lands by sending the command until it shows landed on sensors
        """
        start_time = time.time()

        while (self.sensors.flying_state not in ("landing", "landed") and (time.time() - start_time < timeout)):
            if (self.sensors.flying_state == "emergency"):
                return
            color_print("trying to land", "INFO")
            success = self.land()
            self.smart_sleep(1)

        while (self.sensors.flying_state != "landed" and (time.time() - start_time < timeout)):
            if (self.sensors.flying_state == "emergency"):
                return
            self.smart_sleep(1)
Beispiel #13
0
    def _safe_ble_write(self, characteristic, packet):
        """
        Write to the specified BLE characteristic but first ensure the connection is valid

        :param characteristic:
        :param packet:
        :return:
        """

        success = False

        while (not success):
            try:
                characteristic.write(packet)
                success = True
            except BTLEException:
                color_print("reconnecting to send packet", "WARN")
                self._reconnect(3)
Beispiel #14
0
    def send_command_packet_ack(self, packet):
        """
        Sends the actual packet on the ack channel.  Internal function only.

        :param packet: packet constructed according to the command rules (variable size, constructed elsewhere)
        :return: True if the command was sent and False otherwise
        """
        try_num = 0
        self._set_command_received('SEND_WITH_ACK', False)
        while (try_num < self.max_packet_retries and not self.command_received['SEND_WITH_ACK']):
            color_print("sending command packet on try %d" % try_num, 2)
            self._safe_ble_write(characteristic=self.send_characteristics['SEND_WITH_ACK'], packet=packet)
            #self.send_characteristics['SEND_WITH_ACK'].write(packet)
            try_num += 1
            color_print("sleeping for a notification", 2)
            #notify = self.drone.waitForNotifications(1.0)
            self.smart_sleep(0.5)
            #color_print("awake %s " % notify, 2)

        return self.command_received['SEND_WITH_ACK']
Beispiel #15
0
    def _reconnect(self, num_retries):
        """
        Reconnect to the drone (assumed the BLE crashed)

        :param: num_retries is the number of times to retry

        :return: True if it succeeds and False otherwise
        """
        try_num = 1
        success = False
        while (try_num < num_retries and not success):
            try:
                color_print(
                    "trying to re-connect to the minidrone at address %s" %
                    self.address, "INFO")
                self.drone_connection.connect(self.address, "random")
                color_print(
                    "connected!  Asking for services and characteristics",
                    "SUCCESS")
                success = True
            except BTLEException:
                color_print("retrying connections", "INFO")
                try_num += 1

        if (success):
            # do the magic handshake
            self._perform_handshake()

        return success
Beispiel #16
0
    def connect(self, num_retries):
        """
        Connects to the drone and re-tries in case of failure the specified number of times

        :param: num_retries is the number of times to retry

        :return: True if it succeeds and False otherwise
        """

        # first try to connect to the wifi
        try_num = 1
        connected = False
        while (try_num < num_retries and not connected):
            try:
                self._connect()
                connected = True
            except BTLEException:
                color_print("retrying connections", "INFO")
                try_num += 1

        # fall through, return False as something failed
        return connected
Beispiel #17
0
    def connect(self, num_retries):
        """
        Connects to the drone

        :param num_retries: maximum number of retries

        :return: True if the connection succeeded and False otherwise
        """

        if ("Mambo" not in self.drone_type):
            print("Setting up mDNS listener since this is not a Mambo")
            #parrot's latest mambo firmware (3.0.26 broke all of the mDNS services so this is (temporarily) commented
            #out but it is backwards compatible and will work with the hard-coded addresses for now.
            zeroconf = Zeroconf()
            listener = mDNSListener(self)

            print("Making a browser for %s" % self.mdns_address)

            browser = ServiceBrowser(zeroconf, self.mdns_address, listener)

            # basically have to sleep until the info comes through on the listener
            num_tries = 0
            while (num_tries < num_retries and not self.is_connected):
                time.sleep(1)
                num_tries += 1

            # if we didn't hear the listener, return False
            if (not self.is_connected):
                color_print(
                    "connection failed: did you remember to connect your machine to the Drone's wifi network?",
                    "ERROR")
                return False
            else:
                browser.cancel()

        # perform the handshake and get the UDP info
        handshake = self._handshake(num_retries)
        if (handshake):
            self._create_udp_connection()
            self.listener_thread = threading.Thread(target=self._listen_socket)
            self.listener_thread.start()

            color_print("Success in setting up the wifi network to the drone!",
                        "SUCCESS")
            return True
        else:
            color_print("Error: TCP handshake failed.", "ERROR")
            return False
Beispiel #18
0
    def connect(self, num_retries):
        """
        Connects to the drone

        :param num_retries: maximum number of retries

        :return: True if the connection succeeded and False otherwise
        """

        zeroconf = Zeroconf()
        listener = mDNSListener(self)

        browser = ServiceBrowser(zeroconf, self.mdns_address, listener)

        # basically have to sleep until the info comes through on the listener
        num_tries = 0
        while (num_tries < num_retries and not self.is_connected):
            time.sleep(1)
            num_tries += 1

        # if we didn't hear the listener, return False
        if (not self.is_connected):
            color_print(
                "connection failed: did you remember to connect your machine to the Drone's wifi network?",
                "ERROR")
            return False
        else:
            browser.cancel()

        # perform the handshake and get the UDP info
        handshake = self._handshake(num_retries)
        if (handshake):
            self._create_udp_connection()
            self.listener_thread = threading.Thread(target=self._listen_socket)
            self.listener_thread.start()

            color_print("Success in setting up the wifi network to the drone!",
                        "SUCCESS")
            return True
        else:
            color_print("Error: TCP handshake failed.", "ERROR")
            return False
Beispiel #19
0
    def __init__(self, drone, drone_type="Bebop2"):
        """
        Can be a connection to a Bebop, Bebop2 or a Mambo right now

        :param type: type of drone to connect to
        """
        self.is_connected = False
        if (drone_type not in ("Bebop", "Bebop2", "Mambo")):
            color_print(
                "Error: only type Bebop and Mambo are currently supported",
                "ERROR")
            return

        self.drone = drone

        self.drone_type = drone_type
        self.udp_send_port = 44444  # defined during the handshake except not on Mambo after 3.0.26 firmware
        self.udp_receive_port = 43210
        self.is_listening = True  # for the UDP listener

        if (drone_type is "Bebop"):
            self.mdns_address = "_arsdk-0901._udp.local."
            #Bebop video streaming
            self.stream_port = 55004
            self.stream_control_port = 55005
        elif (drone_type is "Bebop2"):
            self.mdns_address = "_arsdk-090c._udp.local."
            #Bebop video streaming
            self.stream_port = 55004
            self.stream_control_port = 55005
        elif (drone_type is "Mambo"):
            self.mdns_address = "_arsdk-090b._udp.local."

        # map of the data types by name (for outgoing packets)
        self.data_types_by_name = {
            'ACK': 1,
            'DATA_NO_ACK': 2,
            'LOW_LATENCY_DATA': 3,
            'DATA_WITH_ACK': 4
        }

        # map of the incoming data types by number (to figure out if we need to ack etc)
        self.data_types_by_number = {
            1: 'ACK',
            2: 'DATA_NO_ACK',
            3: 'LOW_LATENCY_DATA',
            4: 'DATA_WITH_ACK'
        }

        self.sequence_counter = {
            'PONG': 0,
            'SEND_NO_ACK': 0,
            'SEND_WITH_ACK': 0,
            'SEND_HIGH_PRIORITY': 0,
            'VIDEO_ACK': 0,
            'ACK_DRONE_DATA': 0,
            'NO_ACK_DRONE_DATA': 0,
            'VIDEO_DATA': 0,
        }

        self.buffer_ids = {
            'PING': 0,  # pings from device
            'PONG': 1,  # respond to pings
            'SEND_NO_ACK':
            10,  # not-ack commandsandsensors (piloting and camera rotations)
            'SEND_WITH_ACK':
            11,  # ack commandsandsensors (all piloting commandsandsensors)
            'SEND_HIGH_PRIORITY': 12,  # emergency commandsandsensors
            'VIDEO_ACK': 13,  # ack for video
            'ACK_DRONE_DATA': 127,  # drone data that needs an ack
            'NO_ACK_DRONE_DATA':
            126,  # data from drone (including battery and others), no ack
            'VIDEO_DATA': 125,  # video data
            'ACK_FROM_SEND_WITH_ACK':
            139  # 128 + buffer id for 'SEND_WITH_ACK' is 139
        }

        self.data_buffers = (self.buffer_ids['ACK_DRONE_DATA'],
                             self.buffer_ids['NO_ACK_DRONE_DATA'])

        # store whether a command was acked
        self.command_received = {
            'SEND_WITH_ACK': False,
            'SEND_HIGH_PRIORITY': False,
            'ACK_COMMAND': False
        }

        # maximum number of times to try a packet before assuming it failed
        self.max_packet_retries = 1

        # threading lock for waiting
        self._lock = threading.Lock()
Beispiel #20
0
    print("Prepare for take-off...")

    # Set safe indoor/outdoor parameters
    print("Set indoor parameters...")
    max_tilt = 15
    vertical_speed = 2  #1.5
    max_altitude = 1.5
    max_rotation_speed = 150
    tilt_speed = 200
    bebop.set_max_tilt(max_tilt)
    bebop.set_max_vertical_speed(vertical_speed)
    bebop.set_max_altitude(max_altitude)
    bebop.set_max_rotation_speed(max_rotation_speed)
    bebop.set_max_tilt_rotation_speed(tilt_speed)
    color_print("Indoor parameters set: OK", "SUCCESS")

    # Get initial sensor data_type
    print("--------- SENSOR DATA ----------")
    print("Battery: ", bebop.sensors.battery, "%")
    print("Flying state:", bebop.sensors.flying_state)
    print("Altitude: ", max_altitude, " m")
    print("Pitch/roll rotation speed (degrees): ", tilt_speed)
    print("Tilt (degrees): ", max_tilt)
    print("Vertical speed: ", vertical_speed, " m/s")
    print("Yaw rotation speed (degrees): ", max_rotation_speed)
    print("--------------------------------")

    # Take-off the ground
    color_print("Take-off set: OK", "SUCCESS")
    bebop.safe_takeoff(10)
Beispiel #21
0
def get():
    # Get the character
    inkey = _Getch()
    # Poll for character from keyboard until there is one
    while (1):
        k = inkey()
        if k != '': break
    # "Switch" statement for each of drone commands
    if k == 'w':
        print("Forwards")
        direction(0, 10, 0, 0)
    elif k == 's':
        print("Backwards")
        direction(0, -10, 0, 0)
    elif k == 'd':
        print("Right")
        direction(10, 0, 0, 0)
    elif k == 'a':
        print("Left")
        direction(-10, 0, 0, 0)
    elif k == 'e':
        print("Yaw right")
        direction(0, 0, 5, 0)
    elif k == 'q':
        print("Yaw left")
        direction(0, 0, -5, 0)
    elif k == 'l':
        print("Landing")
        landing()
    elif k == 't' and bebop.sensors.flying_state is not "hovering" or not "flying":
        print("Taking-off")
        takeoff()
    elif k == 'r':
        print("Climbing")
        direction(0, 0, 0, 5)
    elif k == 'f':
        print("Descending")
        direction(0, 0, 0, -5)
    elif k == 'b':
        print("Do a back-flip")
        backflip()
    elif k == 'n':
        print("Do a front-flip")
        frontflip()
    # This is not secured, one person can press c or k
    # and we might lost connection with drone whereas
    # this is in the air maybe someone can make something with this

    # Update: safety added for disconnecting and exiting the program
    # by polling the user for yes/no answer
    elif k == 'i':
        print("Do you want to disconnect from the drone? (Y(es) or N(o))")
        ans = input()
        if ans == 'Y' or ans == 'y' or ans == 'Yes' or ans == 'yes':
            print("Disconnecting (don't forget to exit (q))")
            #bebopVision.close_video()
            disconnect()
        elif ans == 'N' or ans == 'n' or ans == 'No' or ans == 'no':
            pass
        else:
            print("Please give a sensible answer! (Y(es) or N(o))")
    elif k == 'p':
        print("Do you want to close the program? (Y(es) or N(o))")
        ans = input()
        if ans == 'Y' or ans == 'y' or ans == 'Yes' or ans == 'yes':
            print("Closing the program")
            #bebopVision.close_video()
            disconnect()
            exit()
        elif ans == 'N' or ans == 'n' or ans == 'No' or ans == 'no':
            pass
        else:
            print("Please give a sensible answer! (Y(es) or N(o))")
    # If something goes wrong, press ctrl+c to land the drone immediately
    elif ord(k) == 0x03:
        color_print("PANIC: initiating emergency landing", "ERROR")
        bebop.emergency_land()
        disconnect()
        exit()
    else:
        print("Not defined! (Have you turned on Caps lock?)")
Beispiel #22
0
    def extract_sensor_values(self, data):
        """
        Extract the sensor values from the data in the BLE packet
        :param data: BLE packet of sensor data
        :return: a list of tuples of (sensor name, sensor value, sensor enum, header_tuple)
        """
        sensor_list = []
        #print("updating sensors with ")
        try:
            header_tuple = struct.unpack_from("<BBH", data)
        except:
            color_print("Error: tried to parse a bad sensor packet", "ERROR")
            return None

        #print(header_tuple)
        (names, data_sizes) = self._parse_sensor_tuple(header_tuple)
        #print("name of sensor is %s" % names)
        #print("data size is %s" % data_sizes)

        packet_offset = 4
        if names is not None:
            for idx, name in enumerate(names):
                data_size = data_sizes[idx]
                try:
                    # figure out how to parse the data
                    (format_string, new_offset) = get_data_format_and_size(
                        data[packet_offset:], data_size)

                    if (new_offset == 0):
                        # this is usually a boolean flag stating that values have changed so set the value to True
                        # and let it return the name
                        sensor_data = True
                    else:
                        # real data, parse it
                        sensor_data = struct.unpack_from(format_string,
                                                         data,
                                                         offset=packet_offset)
                        sensor_data = sensor_data[0]
                        if (data_size == "string"):
                            packet_offset += len(sensor_data)
                        else:
                            packet_offset += new_offset
                except Exception as e:
                    sensor_data = None
                    #print(header_tuple)
                    color_print("Error parsing data for sensor", "ERROR")
                    print(e)
                    print("name of sensor is %s" % names)
                    print("data size is %s" % data_sizes)
                    print(len(data))
                    print(4 * (idx + 1))

                #print("%s %s %s" % (name,idx,sensor_data))
                #color_print("updating the sensor!", "NONE")
                sensor_list.append(
                    [name, sensor_data, self.sensor_tuple_cache, header_tuple])

            return sensor_list

        else:
            #color_print("Could not find sensor in list - ignoring for now.  Packet info below.", "ERROR")
            #print(header_tuple)
            #print(names)
            return None
Beispiel #23
0
    def _connect(self):
        """
        Connect to the minidrone to prepare for flying - includes getting the services and characteristics
        for communication

        :return: throws an error if the drone connection failed.  Returns void if nothing failed.
        """
        color_print(
            "trying to connect to the minidrone at address %s" % self.address,
            "INFO")
        self.drone_connection.connect(self.address, "random")
        color_print("connected!  Asking for services and characteristics",
                    "SUCCESS")

        # re-try until all services have been found
        allServicesFound = False

        # used for notifications
        handle_map = dict()

        while not allServicesFound:
            # get the services
            self.services = self.drone_connection.getServices()

            # loop through the services
            for s in self.services:
                hex_str = self._get_byte_str_from_uuid(s.uuid, 3, 4)

                # store the characteristics for receive & send
                if (self.service_uuids[hex_str] ==
                        'ARCOMMAND_RECEIVING_SERVICE'):
                    # only store the ones used to receive data
                    for c in s.getCharacteristics():
                        hex_str = self._get_byte_str_from_uuid(c.uuid, 4, 4)
                        if hex_str in self.characteristic_receive_uuids:
                            self.receive_characteristics[
                                self.characteristic_receive_uuids[hex_str]] = c
                            handle_map[c.getHandle()] = hex_str

                elif (self.service_uuids[hex_str] ==
                      'ARCOMMAND_SENDING_SERVICE'):
                    # only store the ones used to send data
                    for c in s.getCharacteristics():
                        hex_str = self._get_byte_str_from_uuid(c.uuid, 4, 4)
                        if hex_str in self.characteristic_send_uuids:
                            self.send_characteristics[
                                self.characteristic_send_uuids[hex_str]] = c

                elif (self.service_uuids[hex_str] == 'UPDATE_BLE_FTP'):
                    # store the FTP info
                    for c in s.getCharacteristics():
                        hex_str = self._get_byte_str_from_uuid(c.uuid, 4, 4)
                        if hex_str in self.characteristic_ftp_uuids:
                            self.ftp_characteristics[
                                self.characteristic_ftp_uuids[hex_str]] = c

                elif (self.service_uuids[hex_str] == 'NORMAL_BLE_FTP_SERVICE'):
                    # store the FTP info
                    for c in s.getCharacteristics():
                        hex_str = self._get_byte_str_from_uuid(c.uuid, 4, 4)
                        if hex_str in self.characteristic_ftp_uuids:
                            self.ftp_characteristics[
                                self.characteristic_ftp_uuids[hex_str]] = c

                # need to register for notifications and write 0100 to the right handles
                # this is sort of magic (not in the docs!) but it shows up on the forum here
                # http://forum.developer.parrot.com/t/minimal-ble-commands-to-send-for-take-off/1686/2
                # Note this code snippet below more or less came from the python example posted to that forum (I adapted it to my interface)
                for c in s.getCharacteristics():
                    if self._get_byte_str_from_uuid(c.uuid, 3, 4) in \
                            ['fb0f', 'fb0e', 'fb1b', 'fb1c', 'fd22', 'fd23', 'fd24', 'fd52', 'fd53', 'fd54']:
                        self.handshake_characteristics[
                            self._get_byte_str_from_uuid(c.uuid, 3, 4)] = c

            # check to see if all 8 characteristics were found
            allServicesFound = True
            for r_id in self.characteristic_receive_uuids.values():
                if r_id not in self.receive_characteristics:
                    color_print("setting to false in receive on %s" % r_id)
                    allServicesFound = False

            for s_id in self.characteristic_send_uuids.values():
                if s_id not in self.send_characteristics:
                    color_print("setting to false in send")
                    allServicesFound = False

            for f_id in self.characteristic_ftp_uuids.values():
                if f_id not in self.ftp_characteristics:
                    color_print("setting to false in ftp")
                    allServicesFound = False

            # and ensure all handshake characteristics were found
            if len(self.handshake_characteristics.keys()) != 10:
                color_print("setting to false in len")
                allServicesFound = False

        # do the magic handshake
        self._perform_handshake()

        # initialize the delegate to handle notifications
        self.drone_connection.setDelegate(
            MinidroneDelegate(handle_map, self.minidrone, self))
Beispiel #24
0
 def __init__(self, handle_map, minidrone, ble_connection):
     DefaultDelegate.__init__(self)
     self.handle_map = handle_map
     self.minidrone = minidrone
     self.ble_connection = ble_connection
     color_print("initializing notification delegate", "INFO")