diff --git a/cflib/__init__.py b/cflib/__init__.py index 536acc1111695aade66f938f03689f8a10d71d4c..516ffc08872c4d6c703417d33cc23b957c6a9932 100644 --- a/cflib/__init__.py +++ b/cflib/__init__.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ The Crazyflie Micro Quadcopter library API used to communicate with the Crazyflie Micro Quadcopter via a communication link. diff --git a/cflib/bootloader/__init__.py b/cflib/bootloader/__init__.py index 4e6bec5ca53592c658692e144dd7035a6e7c9c98..a0c349659c4688c75fbc344d8f1489c30934889c 100644 --- a/cflib/bootloader/__init__.py +++ b/cflib/bootloader/__init__.py @@ -20,24 +20,24 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Bootloading utilities for the Crazyflie. """ - -from cflib.utils.callbacks import Caller -from .cloader import Cloader -from .boottypes import BootVersion, TargetTypes, Target -import zipfile import json +import logging import sys import time -import logging +import zipfile + +from .boottypes import BootVersion +from .boottypes import Target +from .boottypes import TargetTypes +from .cloader import Cloader +from cflib.utils.callbacks import Caller logger = logging.getLogger(__name__) @@ -62,7 +62,7 @@ class Bootloader: self.buffer_pages = 0 self.flash_pages = 0 self.start_page = 0 - self.cpuid = "N/A" + self.cpuid = 'N/A' self.error_code = 0 self.protocol_version = 0 @@ -113,8 +113,8 @@ class Bootloader: elif self.protocol_version == BootVersion.CF2_PROTO_VER: self._cload.request_info_update(TargetTypes.NRF51) else: - print("Bootloader protocol 0x{:X} not " - "supported!".self.protocol_version) + print('Bootloader protocol 0x{:X} not ' + 'supported!'.self.protocol_version) return started @@ -132,15 +132,15 @@ class Bootloader: target = self._cload.targets[0xFF] config_page = target.flash_pages - 1 - to_flash = {"target": target, "data": data, "type": "CF1 config", - "start_page": config_page} + to_flash = {'target': target, 'data': data, 'type': 'CF1 config', + 'start_page': config_page} self._internal_flash(target=to_flash) def flash(self, filename, targets): for target in targets: if TargetTypes.from_string(target) not in self._cload.targets: - print("Target {} not found by bootloader".format(target)) + print('Target {} not found by bootloader'.format(target)) return False files_to_flash = () @@ -148,9 +148,9 @@ class Bootloader: # Read the manifest (don't forget to check so there is one!) try: zf = zipfile.ZipFile(filename) - js = zf.read("manifest.json").decode("UTF-8") + js = zf.read('manifest.json').decode('UTF-8') j = json.loads(js) - files = j["files"] + files = j['files'] platform_id = self._get_platform_id() files_for_platform = self._filter_platform(files, platform_id) if len(targets) == 0: @@ -160,7 +160,7 @@ class Bootloader: zip_targets = self._extract_zip_targets(files_for_platform) except KeyError as e: print(e) - print("No manifest.json in {}".format(filename)) + print('No manifest.json in {}'.format(filename)) return try: @@ -169,40 +169,40 @@ class Bootloader: t = targets[target] for type in t: file_to_flash = {} - current_target = "{}-{}".format(target, type) - file_to_flash["type"] = type + current_target = '{}-{}'.format(target, type) + file_to_flash['type'] = type # Read the data, if this fails we bail - file_to_flash["target"] = self._cload.targets[ + file_to_flash['target'] = self._cload.targets[ TargetTypes.from_string(target)] - file_to_flash["data"] = zf.read( - zip_targets[target][type]["filename"]) - file_to_flash["start_page"] = file_to_flash[ - "target"].start_page + file_to_flash['data'] = zf.read( + zip_targets[target][type]['filename']) + file_to_flash['start_page'] = file_to_flash[ + 'target'].start_page files_to_flash += (file_to_flash,) except KeyError as e: - print("Could not find a file for {} in {}".format( + print('Could not find a file for {} in {}'.format( current_target, filename)) return False else: if len(targets) != 1: - print("Not an archive, must supply one target to flash") + print('Not an archive, must supply one target to flash') else: file_to_flash = {} - file_to_flash["type"] = "binary" + file_to_flash['type'] = 'binary' f = open(filename, 'rb') for t in targets: - file_to_flash["target"] = self._cload.targets[ + file_to_flash['target'] = self._cload.targets[ TargetTypes.from_string(t)] - file_to_flash["type"] = targets[t][0] - file_to_flash["start_page"] = file_to_flash[ - "target"].start_page - file_to_flash["data"] = f.read() + file_to_flash['type'] = targets[t][0] + file_to_flash['start_page'] = file_to_flash[ + 'target'].start_page + file_to_flash['data'] = f.read() f.close() files_to_flash += (file_to_flash,) if not self.progress_cb: - print("") + print('') file_counter = 0 for target in files_to_flash: @@ -213,7 +213,7 @@ class Bootloader: result = {} for file in files: file_info = files[file] - file_platform = file_info["platform"] + file_platform = file_info['platform'] if platform_id == file_platform: result[file] = file_info return result @@ -223,20 +223,20 @@ class Bootloader: for file in files: file_name = file file_info = files[file] - file_target = file_info["target"] - file_type = file_info["type"] + file_target = file_info['target'] + file_type = file_info['type'] if file_target not in zip_targets: zip_targets[file_target] = {} zip_targets[file_target][file_type] = { - "filename": file_name} + 'filename': file_name} return zip_targets def _extract_targets_from_manifest_files(self, files): targets = {} for file in files: file_info = files[file] - file_target = file_info["target"] - file_type = file_info["type"] + file_target = file_info['target'] + file_type = file_info['type'] if file_target in targets: targets[file_target] += (file_type,) else: @@ -256,10 +256,10 @@ class Bootloader: def _internal_flash(self, target, current_file_number=1, total_files=1): - image = target["data"] - t_data = target["target"] + image = target['data'] + t_data = target['target'] - start_page = target["start_page"] + start_page = target['start_page'] # If used from a UI we need some extra things for reporting progress factor = (100.0 * t_data.page_size) / len(image) @@ -267,29 +267,29 @@ class Bootloader: if self.progress_cb: self.progress_cb( - "({}/{}) Starting...".format(current_file_number, total_files), + '({}/{}) Starting...'.format(current_file_number, total_files), int(progress)) else: sys.stdout.write( - "Flashing {} of {} to {} ({}): ".format( + 'Flashing {} of {} to {} ({}): '.format( current_file_number, total_files, - TargetTypes.to_string(t_data.id), target["type"])) + TargetTypes.to_string(t_data.id), target['type'])) sys.stdout.flush() if len(image) > ((t_data.flash_pages - start_page) * t_data.page_size): if self.progress_cb: self.progress_cb( - "Error: Not enough space to flash the image file.", + 'Error: Not enough space to flash the image file.', int(progress)) else: - print("Error: Not enough space to flash the image file.") + print('Error: Not enough space to flash the image file.') raise Exception() if not self.progress_cb: - logger.info(("%d bytes (%d pages) " % ( + logger.info(('%d bytes (%d pages) ' % ( (len(image) - 1), int(len(image) / t_data.page_size) + 1))) - sys.stdout.write(("%d bytes (%d pages) " % ( + sys.stdout.write(('%d bytes (%d pages) ' % ( (len(image) - 1), int(len(image) / t_data.page_size) + 1))) sys.stdout.flush() @@ -309,39 +309,39 @@ class Bootloader: if self.progress_cb: progress += factor - self.progress_cb("({}/{}) Uploading buffer to {}...".format( + self.progress_cb('({}/{}) Uploading buffer to {}...'.format( current_file_number, total_files, TargetTypes.to_string(t_data.id)), int(progress)) else: - sys.stdout.write(".") + sys.stdout.write('.') sys.stdout.flush() # Flash when the complete buffers are full if ctr >= t_data.buffer_pages: if self.progress_cb: - self.progress_cb("({}/{}) Writing buffer to {}...".format( + self.progress_cb('({}/{}) Writing buffer to {}...'.format( current_file_number, total_files, TargetTypes.to_string(t_data.id)), int(progress)) else: - sys.stdout.write("%d" % ctr) + sys.stdout.write('%d' % ctr) sys.stdout.flush() if not self._cload.write_flash(t_data.addr, 0, start_page + i - (ctr - 1), ctr): if self.progress_cb: self.progress_cb( - "Error during flash operation (code %d)".format( + 'Error during flash operation (code %d)'.format( self._cload.error_code), int(progress)) else: - print("\nError during flash operation (code %d). " - "Maybe wrong radio link?" % + print('\nError during flash operation (code %d). ' + 'Maybe wrong radio link?' % self._cload.error_code) raise Exception() @@ -349,13 +349,13 @@ class Bootloader: if ctr > 0: if self.progress_cb: - self.progress_cb("({}/{}) Writing buffer to {}...".format( + self.progress_cb('({}/{}) Writing buffer to {}...'.format( current_file_number, total_files, TargetTypes.to_string(t_data.id)), int(progress)) else: - sys.stdout.write("%d" % ctr) + sys.stdout.write('%d' % ctr) sys.stdout.flush() if not self._cload.write_flash( t_data.addr, 0, @@ -363,26 +363,26 @@ class Bootloader: (ctr - 1)), ctr): if self.progress_cb: self.progress_cb( - "Error during flash operation (code %d)".format( + 'Error during flash operation (code %d)'.format( self._cload.error_code), int(progress)) else: - print("\nError during flash operation (code %d). Maybe" - " wrong radio link?" % self._cload.error_code) + print('\nError during flash operation (code %d). Maybe' + ' wrong radio link?' % self._cload.error_code) raise Exception() if self.progress_cb: self.progress_cb( - "({}/{}) Flashing done!".format(current_file_number, + '({}/{}) Flashing done!'.format(current_file_number, total_files), int(100)) else: - print("") + print('') def _get_platform_id(self): """Get platform identifier used in the zip manifest for curr copter""" - identifier = "cf1" + identifier = 'cf1' if (BootVersion.is_cf2(self.protocol_version)): - identifier = "cf2" + identifier = 'cf2' return identifier diff --git a/cflib/bootloader/boottypes.py b/cflib/bootloader/boottypes.py index b637e98abfe1c16d62b0186d3e28ffb90a57ae34..8a73f2543d2063779959874ac2c7539a055f0d56 100644 --- a/cflib/bootloader/boottypes.py +++ b/cflib/bootloader/boottypes.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Bootloading utilities for the Crazyflie. """ @@ -43,10 +41,10 @@ class BootVersion: def to_ver_string(ver): if (ver == BootVersion.CF1_PROTO_VER_0 or ver == BootVersion. CF1_PROTO_VER_1): - return "Crazyflie Nano Quadcopter (1.0)" + return 'Crazyflie Nano Quadcopter (1.0)' if ver == BootVersion.CF2_PROTO_VER: - return "Crazyflie 2.0" - return "Unknown" + return 'Crazyflie 2.0' + return 'Unknown' @staticmethod def is_cf2(ver): @@ -60,21 +58,22 @@ class TargetTypes: @staticmethod def to_string(target): if target == TargetTypes.STM32: - return "stm32" + return 'stm32' if target == TargetTypes.NRF51: - return "nrf51" - return "Unknown" + return 'nrf51' + return 'Unknown' @staticmethod def from_string(name): - if name == "stm32": + if name == 'stm32': return TargetTypes.STM32 - if name == "nrf51": + if name == 'nrf51': return TargetTypes.NRF51 return 0 class Target: + def __init__(self, id): self.id = id self.protocol_version = 0xFF @@ -82,16 +81,16 @@ class Target: self.buffer_pages = 0 self.flash_pages = 0 self.start_page = 0 - self.cpuid = "" + self.cpuid = '' self.data = None def __str__(self): - ret = "" - ret += "Target info: {} (0x{:X})\n".format( + ret = '' + ret += 'Target info: {} (0x{:X})\n'.format( TargetTypes.to_string(self.id), self.id) - ret += "Flash pages: %d | Page size: %d | Buffer pages: %d |" \ - " Start page: %d\n" % (self.flash_pages, self.page_size, + ret += 'Flash pages: %d | Page size: %d | Buffer pages: %d |' \ + ' Start page: %d\n' % (self.flash_pages, self.page_size, self.buffer_pages, self.start_page) - ret += "%d KBytes of flash available for firmware image." % ( + ret += '%d KBytes of flash available for firmware image.' % ( (self.flash_pages - self.start_page) * self.page_size / 1024) return ret diff --git a/cflib/bootloader/cloader.py b/cflib/bootloader/cloader.py index 1bffeb15bfd1b741f8960920deb587550ec9ff73..6800b27da4336ad07afe2ed7c41530eae03682b2 100644 --- a/cflib/bootloader/cloader.py +++ b/cflib/bootloader/cloader.py @@ -20,27 +20,24 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Crazyflie radio bootloader for flashing firmware. """ - import logging - -import time -import struct import math import random +import struct +import time import cflib.crtp -from cflib.crtp.crtpstack import CRTPPacket, CRTPPort - -from .boottypes import TargetTypes, Target +from .boottypes import Target +from .boottypes import TargetTypes +from cflib.crtp.crtpstack import CRTPPacket +from cflib.crtp.crtpstack import CRTPPort __author__ = 'Bitcraze AB' __all__ = ['Cloader'] @@ -66,7 +63,7 @@ class Cloader: self.buffer_pages = 0 self.flash_pages = 0 self.start_page = 0 - self.cpuid = "N/A" + self.cpuid = 'N/A' self.error_code = 0 self.protocol_version = 0xFF @@ -75,7 +72,7 @@ class Cloader: self.targets = {} self.mapping = None - self._available_boot_uri = ("radio://0/110/2M", "radio://0/0/2M") + self._available_boot_uri = ('radio://0/110/2M', 'radio://0/0/2M') def close(self): """ Close the link """ @@ -83,7 +80,7 @@ class Cloader: self.link.close() def scan_for_bootloader(self): - link = cflib.crtp.get_link_driver("radio://0") + link = cflib.crtp.get_link_driver('radio://0') ts = time.time() res = () while len(res) == 0 and (time.time() - ts) < 10: @@ -105,26 +102,26 @@ class Cloader: pk = self.link.receive_packet(1) while ((not pk or pk.header != 0xFF or - struct.unpack("<BB", pk.data[0:2]) != (target_id, 0xFF) + struct.unpack('<BB', pk.data[0:2]) != (target_id, 0xFF) ) and retry_counter >= 0): pk = self.link.receive_packet(1) retry_counter -= 1 if pk: - new_address = (0xb1,) + struct.unpack("<BBBB", pk.data[2:6][::-1]) + new_address = (0xb1,) + struct.unpack('<BBBB', pk.data[2:6][::-1]) pk = CRTPPacket() pk.set_header(0xFF, 0xFF) pk.data = (target_id, 0xF0, 0x00) self.link.send_packet(pk) - addr = int(struct.pack("B" * 5, *new_address).encode('hex'), 16) + addr = int(struct.pack('B' * 5, *new_address).encode('hex'), 16) time.sleep(0.2) self.link.close() time.sleep(0.2) self.link = cflib.crtp.get_link_driver( - "radio://0/0/2M/{}".format(addr)) + 'radio://0/0/2M/{}'.format(addr)) return True else: @@ -205,7 +202,7 @@ class Cloader: return False if (pk.header == 0xFF and struct.unpack( - "B" * len(pk.data), pk.data)[:2] == (target_id, 0xFF)): + 'B' * len(pk.data), pk.data)[:2] == (target_id, 0xFF)): # Difference in CF1 and CF2 (CPU ID) if target_id == 0xFE: pk.data = (target_id, 0xF0, 0x01) @@ -246,23 +243,23 @@ class Cloader: This function works only with crazyradio CRTP link. """ - logging.debug("Setting bootloader radio address to" - " {}".format(new_address)) + logging.debug('Setting bootloader radio address to' + ' {}'.format(new_address)) if len(new_address) != 5: - raise Exception("Radio address should be 5 bytes long") + raise Exception('Radio address should be 5 bytes long') self.link.pause() for _ in range(10): - logging.debug("Trying to set new radio address") + logging.debug('Trying to set new radio address') self.link.cradio.set_address((0xE7,) * 5) pkdata = (0xFF, 0xFF, 0x11) + tuple(new_address) self.link.cradio.send_packet(pkdata) self.link.cradio.set_address(tuple(new_address)) if self.link.cradio.send_packet((0xff,)).ack: - logging.info("Bootloader set to radio address" - " {}".format(new_address)) + logging.info('Bootloader set to radio address' + ' {}'.format(new_address)) self.link.restart() return True @@ -290,10 +287,10 @@ class Cloader: # Wait for the answer pk = self.link.receive_packet(2) - if (pk and pk.header == 0xFF and struct.unpack("<BB", pk.data[0:2]) == + if (pk and pk.header == 0xFF and struct.unpack('<BB', pk.data[0:2]) == (target_id, 0x10)): - tab = struct.unpack("BBHHHH", pk.data[0:10]) - cpuid = struct.unpack("B" * 12, pk.data[10:22]) + tab = struct.unpack('BBHHHH', pk.data[0:10]) + cpuid = struct.unpack('B' * 12, pk.data[10:22]) if target_id not in self.targets: self.targets[target_id] = Target(target_id) self.targets[target_id].addr = target_id @@ -304,9 +301,9 @@ class Cloader: self.targets[target_id].buffer_pages = tab[3] self.targets[target_id].flash_pages = tab[4] self.targets[target_id].start_page = tab[5] - self.targets[target_id].cpuid = "%02X" % cpuid[0] + self.targets[target_id].cpuid = '%02X' % cpuid[0] for i in cpuid[1:]: - self.targets[target_id].cpuid += ":%02X" % i + self.targets[target_id].cpuid += ':%02X' % i if (self.protocol_version == 0x10 and target_id == TargetTypes.STM32): @@ -324,12 +321,12 @@ class Cloader: pk = self.link.receive_packet(2) - if (pk and pk.header == 0xFF and struct.unpack("<BB", pk.data[0:2]) == + if (pk and pk.header == 0xFF and struct.unpack('<BB', pk.data[0:2]) == (target_id, 0x12)): m = pk.datat[2:] if (len(m) % 2) != 0: - raise Exception("Malformed flash mapping packet") + raise Exception('Malformed flash mapping packet') self.mapping = [] page = 0 @@ -344,7 +341,7 @@ class Cloader: count = 0 pk = CRTPPacket() pk.set_header(0xFF, 0xFF) - pk.data = struct.pack("=BBHH", target_id, 0x14, page, address) + pk.data = struct.pack('=BBHH', target_id, 0x14, page, address) for i in range(0, len(buff)): pk.data.append(buff[i]) @@ -356,7 +353,7 @@ class Cloader: count = 0 pk = CRTPPacket() pk.set_header(0xFF, 0xFF) - pk.data = struct.pack("=BBHH", target_id, 0x14, page, + pk.data = struct.pack('=BBHH', target_id, 0x14, page, i + address + 1) self.link.send_packet(pk) @@ -371,11 +368,11 @@ class Cloader: pk = None retry_counter = 5 while ((not pk or pk.header != 0xFF or - struct.unpack("<BB", pk.data[0:2]) != (addr, 0x1C)) and + struct.unpack('<BB', pk.data[0:2]) != (addr, 0x1C)) and retry_counter >= 0): pk = CRTPPacket() pk.set_header(0xFF, 0xFF) - pk.data = struct.pack("<BBHH", addr, 0x1C, page, (i * 25)) + pk.data = struct.pack('<BBHH', addr, 0x1C, page, (i * 25)) self.link.send_packet(pk) pk = self.link.receive_packet(1) @@ -396,11 +393,11 @@ class Cloader: retry_counter = 5 # print "Flasing to 0x{:X}".format(addr) while ((not pk or pk.header != 0xFF or - struct.unpack("<BB", pk.data[0:2]) != (addr, 0x18)) and + struct.unpack('<BB', pk.data[0:2]) != (addr, 0x18)) and retry_counter >= 0): pk = CRTPPacket() pk.set_header(0xFF, 0xFF) - pk.data = struct.pack("<BBHHH", addr, 0x18, page_buffer, + pk.data = struct.pack('<BBHHH', addr, 0x18, page_buffer, target_page, page_count) self.link.send_packet(pk) pk = self.link.receive_packet(1) @@ -418,6 +415,6 @@ class Cloader: """Decode the CPU id into a string""" ret = () for i in cpuid.split(':'): - ret += (eval("0x" + i),) + ret += (eval('0x' + i),) return ret diff --git a/cflib/crazyflie/__init__.py b/cflib/crazyflie/__init__.py index 698fef1eca0b632a9b1f62c83401ab91f4bc1ef6..4e8a47ed2057f328fffd66f8dd2fa3e49e075844 100644 --- a/cflib/crazyflie/__init__.py +++ b/cflib/crazyflie/__init__.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ The Crazyflie module is used to easily connect/send/receive data from a Crazyflie. @@ -34,25 +32,22 @@ Each function in the Crazyflie has a class in the module that can be used to access that functionality. The same design is then used in the Crazyflie firmware which makes the mapping 1:1 in most cases. """ - +import datetime import logging - import time -import datetime -from threading import Thread -from threading import Timer, Lock from collections import namedtuple +from threading import Lock +from threading import Thread +from threading import Timer +import cflib.crtp from .commander import Commander from .console import Console -from .param import Param from .log import Log -from .toccache import TocCache from .mem import Memory +from .param import Param from .platformservice import PlatformService - -import cflib.crtp - +from .toccache import TocCache from cflib.utils.callbacks import Caller __author__ = 'Bitcraze AB' @@ -116,7 +111,7 @@ class Crazyflie(): self.mem = Memory(self) self.platform = PlatformService(self) - self.link_uri = "" + self.link_uri = '' # Used for retry when no reply was sent back self.packet_received.add_callback(self._check_for_initial_packet_cb) @@ -130,22 +125,22 @@ class Crazyflie(): # Connect callbacks to logger self.disconnected.add_callback( - lambda uri: logger.info("Callback->Disconnected from [%s]", uri)) + lambda uri: logger.info('Callback->Disconnected from [%s]', uri)) self.disconnected.add_callback(self._disconnected) self.link_established.add_callback( - lambda uri: logger.info("Callback->Connected to [%s]", uri)) + lambda uri: logger.info('Callback->Connected to [%s]', uri)) self.connection_lost.add_callback( lambda uri, errmsg: logger.info( - "Callback->Connection lost to [%s]: %s", uri, errmsg)) + 'Callback->Connection lost to [%s]: %s', uri, errmsg)) self.connection_failed.add_callback( lambda uri, errmsg: logger.info( - "Callback->Connected failed to [%s]: %s", uri, errmsg)) + 'Callback->Connected failed to [%s]: %s', uri, errmsg)) self.connection_requested.add_callback( lambda uri: logger.info( - "Callback->Connection initialized[%s]", uri)) + 'Callback->Connection initialized[%s]', uri)) self.connected.add_callback( lambda uri: logger.info( - "Callback->Connection setup finished [%s]", uri)) + 'Callback->Connection setup finished [%s]', uri)) def _disconnected(self, link_uri): """ Callback when disconnected.""" @@ -153,13 +148,13 @@ class Crazyflie(): def _start_connection_setup(self): """Start the connection setup by refreshing the TOCs""" - logger.info("We are connected[%s], request connection setup", + logger.info('We are connected[%s], request connection setup', self.link_uri) self.log.refresh_toc(self._log_toc_updated_cb, self._toc_cache) def _param_toc_updated_cb(self): """Called when the param TOC has been fully updated""" - logger.info("Param TOC finished updating") + logger.info('Param TOC finished updating') self.connected_ts = datetime.datetime.now() self.connected.call(self.link_uri) # Trigger the update for all the parameters @@ -167,17 +162,17 @@ class Crazyflie(): def _mems_updated_cb(self): """Called when the memories have been identified""" - logger.info("Memories finished updating") + logger.info('Memories finished updating') self.param.refresh_toc(self._param_toc_updated_cb, self._toc_cache) def _log_toc_updated_cb(self): """Called when the log TOC has been fully updated""" - logger.info("Log TOC finished updating") + logger.info('Log TOC finished updating') self.mem.refresh(self._mems_updated_cb) def _link_error_cb(self, errmsg): """Called from the link driver when there's an error""" - logger.warning("Got link error callback [%s] in state [%s]", + logger.warning('Got link error callback [%s] in state [%s]', errmsg, self.state) if (self.link is not None): self.link.close() @@ -218,7 +213,7 @@ class Crazyflie(): link_uri, self._link_quality_cb, self._link_error_cb) if not self.link: - message = "No driver found or malformed URI: {}" \ + message = 'No driver found or malformed URI: {}' \ .format(link_uri) logger.warning(message) self.connection_failed.call(link_uri, message) @@ -245,7 +240,7 @@ class Crazyflie(): def close_link(self): """Close the communication link.""" - logger.info("Closing link") + logger.info('Closing link') if (self.link is not None): self.commander.send_setpoint(0, 0, 0, 0) if (self.link is not None): @@ -264,7 +259,7 @@ class Crazyflie(): def _no_answer_do_retry(self, pk, pattern): """Resend packets that we have not gotten answers to""" - logger.info("Resending for pattern %s", pattern) + logger.info('Resending for pattern %s', pattern) # Set the timer to None before trying to send again self.send_packet(pk, expected_reply=pattern, resend=True) @@ -278,12 +273,12 @@ class Crazyflie(): if len(self._answer_patterns) > 0: data = (pk.header,) + tuple(pk.data) for p in list(self._answer_patterns.keys()): - logger.debug("Looking for pattern match on %s vs %s", p, data) + logger.debug('Looking for pattern match on %s vs %s', p, data) if len(p) <= len(data): if p == data[0:len(p)]: match = data[0:len(p)] if len(match) >= len(longest_match): - logger.debug("Found new longest match %s", match) + logger.debug('Found new longest match %s', match) longest_match = match if len(longest_match) > 0: self._answer_patterns[longest_match].cancel() @@ -304,7 +299,7 @@ class Crazyflie(): self.link.needs_resending: pattern = (pk.header,) + expected_reply logger.debug( - "Sending packet and expecting the %s pattern back", + 'Sending packet and expecting the %s pattern back', pattern) new_timer = Timer(timeout, lambda: self._no_answer_do_retry(pk, @@ -315,7 +310,7 @@ class Crazyflie(): # Check if we have gotten an answer, if not try again pattern = expected_reply if pattern in self._answer_patterns: - logger.debug("We want to resend and the pattern is there") + logger.debug('We want to resend and the pattern is there') if self._answer_patterns[pattern]: new_timer = Timer(timeout, lambda: @@ -324,15 +319,15 @@ class Crazyflie(): self._answer_patterns[pattern] = new_timer new_timer.start() else: - logger.debug("Resend requested, but no pattern found: %s", + logger.debug('Resend requested, but no pattern found: %s', self._answer_patterns) self.link.send_packet(pk) self.packet_sent.call(pk) self._send_lock.release() -_CallbackContainer = namedtuple("CallbackConstainer", - "port port_mask channel channel_mask callback") +_CallbackContainer = namedtuple('CallbackConstainer', + 'port port_mask channel channel_mask callback') class _IncomingPacketHandler(Thread): @@ -345,12 +340,12 @@ class _IncomingPacketHandler(Thread): def add_port_callback(self, port, cb): """Add a callback for data that comes on a specific port""" - logger.debug("Adding callback on port [%d] to [%s]", port, cb) + logger.debug('Adding callback on port [%d] to [%s]', port, cb) self.add_header_callback(cb, port, 0, 0xff, 0x0) def remove_port_callback(self, port, cb): """Remove a callback for data that comes on a specific port""" - logger.debug("Removing callback on port [%d] to [%s]", port, cb) + logger.debug('Removing callback on port [%d] to [%s]', port, cb) for port_callback in self.cb: if port_callback.port == port and port_callback.callback == cb: self.cb.remove(port_callback) @@ -390,8 +385,8 @@ class _IncomingPacketHandler(Thread): # the callbacks. import traceback - logger.warning("Exception while doing callback on port" - " [%d]\n\n%s", pk.port, + logger.warning('Exception while doing callback on port' + ' [%d]\n\n%s', pk.port, traceback.format_exc()) if cb.port != 0xFF: found = True diff --git a/cflib/crazyflie/commander.py b/cflib/crazyflie/commander.py index e791887c1e23d702dd03d0d1cd21dddd2ce83333..ed8c0c1d7cdefa60720d2c700f24133a472a7a81 100644 --- a/cflib/crazyflie/commander.py +++ b/cflib/crazyflie/commander.py @@ -20,19 +20,18 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Used for sending control setpoints to the Crazyflie """ - -from cflib.crtp.crtpstack import CRTPPacket, CRTPPort import struct +from cflib.crtp.crtpstack import CRTPPacket +from cflib.crtp.crtpstack import CRTPPort + __author__ = 'Bitcraze AB' __all__ = ['Commander'] @@ -65,7 +64,7 @@ class Commander(): be sent to the copter """ if thrust > 0xFFFF or thrust < 0: - raise ValueError("Thrust must be between 0 and 0xFFFF") + raise ValueError('Thrust must be between 0 and 0xFFFF') if self._x_mode: roll, pitch = 0.707 * (roll - pitch), 0.707 * (roll + pitch) diff --git a/cflib/crazyflie/console.py b/cflib/crazyflie/console.py index 26b9f9fda5e478178b95dffa4308bcbc2a85d669..61df2e466d93d61a4eee27923acdb8be8aaf97f6 100644 --- a/cflib/crazyflie/console.py +++ b/cflib/crazyflie/console.py @@ -20,7 +20,6 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, @@ -29,10 +28,8 @@ Crazyflie console is used to receive characters printed using printf from the firmware. """ - -import struct -from cflib.utils.callbacks import Caller from cflib.crtp.crtpstack import CRTPPort +from cflib.utils.callbacks import Caller __author__ = 'Bitcraze AB' __all__ = ['Console'] @@ -58,6 +55,6 @@ class Console: Callback for data received from the copter. """ # This might be done prettier ;-) - console_text = packet.data.decode("UTF-8") + console_text = packet.data.decode('UTF-8') self.receivedChar.call(console_text) diff --git a/cflib/crazyflie/log.py b/cflib/crazyflie/log.py index ca52eed48496da8712c4acc9292cc7541fc089a8..76dd776a1ba90fc46e0cfef678d3431a242b7c8f 100644 --- a/cflib/crazyflie/log.py +++ b/cflib/crazyflie/log.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Enables logging of variables from the Crazyflie. @@ -62,14 +60,15 @@ States of a configuration: Crazyflie. The configuration will have to be re-added to be used again. """ - -import struct import errno -import sys -from cflib.crtp.crtpstack import CRTPPacket, CRTPPort -from cflib.utils.callbacks import Caller -from .toc import Toc, TocFetcher import logging +import struct + +from .toc import Toc +from .toc import TocFetcher +from cflib.crtp.crtpstack import CRTPPacket +from cflib.crtp.crtpstack import CRTPPort +from cflib.utils.callbacks import Caller __author__ = 'Bitcraze AB' __all__ = ['Log', 'LogTocElement'] @@ -92,9 +91,9 @@ CMD_STOP_LOGGING = 4 CMD_RESET_LOGGING = 5 # Possible states when receiving TOC -IDLE = "IDLE" -GET_TOC_INF = "GET_TOC_INFO" -GET_TOC_ELEMENT = "GET_TOC_ELEMENT" +IDLE = 'IDLE' +GET_TOC_INF = 'GET_TOC_INFO' +GET_TOC_ELEMENT = 'GET_TOC_ELEMENT' # The max size of a CRTP packet payload MAX_LOG_DATA_PACKET_SIZE = 30 @@ -109,8 +108,8 @@ class LogVariable(): TOC_TYPE = 0 MEM_TYPE = 1 - def __init__(self, name="", fetchAs="uint8_t", varType=TOC_TYPE, - storedAs="", address=0): + def __init__(self, name='', fetchAs='uint8_t', varType=TOC_TYPE, + storedAs='', address=0): self.name = name self.fetch_as = LogTocElement.get_id_from_cstring(fetchAs) if (len(storedAs) == 0): @@ -134,7 +133,7 @@ class LogVariable(): return (self.fetch_as | (self.stored_as << 4)) def __str__(self): - return ("LogVariable: name=%s, store=%s, fetch=%s" % + return ('LogVariable: name=%s, store=%s, fetch=%s' % (self.name, LogTocElement.get_cstring_from_id(self.stored_as), LogTocElement.get_cstring_from_id(self.fetch_as))) @@ -220,19 +219,19 @@ class LogConfig(object): pk.data = (CMD_CREATE_BLOCK, self.id) for var in self.variables: if (var.is_toc_variable() is False): # Memory location - logger.debug("Logging to raw memory %d, 0x%04X", + logger.debug('Logging to raw memory %d, 0x%04X', var.get_storage_and_fetch_byte(), var.address) pk.data.append(struct.pack('<B', var.get_storage_and_fetch_byte())) pk.data.append(struct.pack('<I', var.address)) else: # Item in TOC - logger.debug("Adding %s with id=%d and type=0x%02X", + logger.debug('Adding %s with id=%d and type=0x%02X', var.name, self.cf.log.toc.get_element_id( var.name), var.get_storage_and_fetch_byte()) pk.data.append(var.get_storage_and_fetch_byte()) pk.data.append(self.cf.log.toc.get_element_id(var.name)) - logger.debug("Adding log block id {}".format(self.id)) + logger.debug('Adding log block id {}'.format(self.id)) self.cf.send_packet(pk, expected_reply=(CMD_CREATE_BLOCK, self.id)) def start(self): @@ -240,10 +239,10 @@ class LogConfig(object): if (self.cf.link is not None): if (self._added is False): self.create() - logger.debug("First time block is started, add block") + logger.debug('First time block is started, add block') else: - logger.debug("Block already registered, starting logging" - " for id=%d", self.id) + logger.debug('Block already registered, starting logging' + ' for id=%d', self.id) pk = CRTPPacket() pk.set_header(5, CHAN_SETTINGS) pk.data = (CMD_START_LOGGING, self.id, self.period) @@ -254,9 +253,9 @@ class LogConfig(object): """Stop the logging for this entry""" if (self.cf.link is not None): if (self.id is None): - logger.warning("Stopping block, but no block registered") + logger.warning('Stopping block, but no block registered') else: - logger.debug("Sending stop logging for block id=%d", self.id) + logger.debug('Sending stop logging for block id=%d', self.id) pk = CRTPPacket() pk.set_header(5, CHAN_SETTINGS) pk.data = (CMD_STOP_LOGGING, self.id) @@ -267,9 +266,9 @@ class LogConfig(object): """Delete this entry in the Crazyflie""" if (self.cf.link is not None): if (self.id is None): - logger.warning("Delete block, but no block registered") + logger.warning('Delete block, but no block registered') else: - logger.debug("LogEntry: Sending delete logging for block id=%d" + logger.debug('LogEntry: Sending delete logging for block id=%d' % self.id) pk = CRTPPacket() pk.set_header(5, CHAN_SETTINGS) @@ -296,14 +295,14 @@ class LogConfig(object): class LogTocElement: """An element in the Log TOC.""" - types = {0x01: ("uint8_t", '<B', 1), - 0x02: ("uint16_t", '<H', 2), - 0x03: ("uint32_t", '<L', 4), - 0x04: ("int8_t", '<b', 1), - 0x05: ("int16_t", '<h', 2), - 0x06: ("int32_t", '<i', 4), - 0x08: ("FP16", '<h', 2), - 0x07: ("float", '<f', 4)} + types = {0x01: ('uint8_t', '<B', 1), + 0x02: ('uint16_t', '<H', 2), + 0x03: ('uint32_t', '<L', 4), + 0x04: ('int8_t', '<b', 1), + 0x05: ('int16_t', '<h', 2), + 0x06: ('int32_t', '<i', 4), + 0x08: ('FP16', '<h', 2), + 0x07: ('float', '<f', 4)} @staticmethod def get_id_from_cstring(name): @@ -311,7 +310,7 @@ class LogTocElement: for key in list(LogTocElement.types.keys()): if (LogTocElement.types[key][0] == name): return key - raise KeyError("Type [%s] not found in LogTocElement.types!" % name) + raise KeyError('Type [%s] not found in LogTocElement.types!' % name) @staticmethod def get_cstring_from_id(ident): @@ -319,8 +318,8 @@ class LogTocElement: try: return LogTocElement.types[ident][0] except KeyError: - raise KeyError("Type [%d] not found in LogTocElement.types" - "!" % ident) + raise KeyError('Type [%d] not found in LogTocElement.types' + '!' % ident) @staticmethod def get_size_from_id(ident): @@ -328,8 +327,8 @@ class LogTocElement: try: return LogTocElement.types[ident][2] except KeyError: - raise KeyError("Type [%d] not found in LogTocElement.types" - "!" % ident) + raise KeyError('Type [%d] not found in LogTocElement.types' + '!' % ident) @staticmethod def get_unpack_string_from_id(ident): @@ -338,7 +337,7 @@ class LogTocElement: return LogTocElement.types[ident][1] except KeyError: raise KeyError( - "Type [%d] not found in LogTocElement.types!" % ident) + 'Type [%d] not found in LogTocElement.types!' % ident) def __init__(self, data=None): """TocElement creator. Data is the binary payload of the element.""" @@ -346,8 +345,8 @@ class LogTocElement: if (data): naming = data[2:] zt = bytearray((0, )) - self.group = naming[:naming.find(zt)].decode("ISO-8859-1") - self.name = naming[naming.find(zt)+1:-1].decode("ISO-8859-1") + self.group = naming[:naming.find(zt)].decode('ISO-8859-1') + self.name = naming[naming.find(zt) + 1:-1].decode('ISO-8859-1') self.ident = data[0] @@ -364,11 +363,11 @@ class Log(): # some of the text messages will look very strange # in the UI, so they are redefined here _err_codes = { - errno.ENOMEM: "No more memory available", - errno.ENOEXEC: "Command not found", - errno.ENOENT: "No such block id", - errno.E2BIG: "Block too large", - errno.EEXIST: "Block already exists" + errno.ENOMEM: 'No more memory available', + errno.ENOEXEC: 'Command not found', + errno.ENOENT: 'No such block id', + errno.E2BIG: 'Block too large', + errno.EEXIST: 'Block already exists' } def __init__(self, crazyflie=None): @@ -398,8 +397,8 @@ class Log(): connected when calling this method, otherwise it will fail.""" if not self.cf.link: - logger.error("Cannot add configs without being connected to a " - "Crazyflie!") + logger.error('Cannot add configs without being connected to a ' + 'Crazyflie!') return # If the log configuration contains variables that we added without @@ -409,9 +408,9 @@ class Log(): var = self.toc.get_element_by_complete_name(name) if not var: logger.warning( - "%s not in TOC, this block cannot be used!", name) + '%s not in TOC, this block cannot be used!', name) logconf.valid = False - raise KeyError("Variable {} not in TOC".format(name)) + raise KeyError('Variable {} not in TOC'.format(name)) # Now that we know what type this variable has, add it to the log # config again with the correct type logconf.add_variable(name, var.ctype) @@ -427,10 +426,10 @@ class Log(): if var.is_toc_variable(): if (self.toc.get_element_by_complete_name(var.name) is None): logger.warning( - "Log: %s not in TOC, this block cannot be used!", + 'Log: %s not in TOC, this block cannot be used!', var.name) logconf.valid = False - raise KeyError("Variable {} not in TOC".format(var.name)) + raise KeyError('Variable {} not in TOC'.format(var.name)) if (size <= MAX_LOG_DATA_PACKET_SIZE and (logconf.period > 0 and logconf.period < 0xFF)): @@ -441,8 +440,8 @@ class Log(): else: logconf.valid = False raise AttributeError( - "The log configuration is too large or has an invalid " - "parameter") + 'The log configuration is too large or has an invalid ' + 'parameter') def refresh_toc(self, refresh_done_callback, toc_cache): """Start refreshing the table of loggale variables""" @@ -476,7 +475,7 @@ class Log(): if (block is not None): if error_status == 0 or error_status == errno.EEXIST: if not block.added: - logger.debug("Have successfully added id=%d", id) + logger.debug('Have successfully added id=%d', id) pk = CRTPPacket() pk.set_header(5, CHAN_SETTINGS) @@ -486,24 +485,24 @@ class Log(): block.added = True else: msg = self._err_codes[error_status] - logger.warning("Error %d when adding id=%d (%s)", + logger.warning('Error %d when adding id=%d (%s)', error_status, id, msg) block.err_no = error_status block.added_cb.call(False) block.error_cb.call(block, msg) else: - logger.warning("No LogEntry to assign block to !!!") + logger.warning('No LogEntry to assign block to !!!') if (cmd == CMD_START_LOGGING): if (error_status == 0x00): - logger.info("Have successfully started logging for id=%d", + logger.info('Have successfully started logging for id=%d', id) if block: block.started = True else: msg = self._err_codes[error_status] - logger.warning("Error %d when starting id=%d (%s)", + logger.warning('Error %d when starting id=%d (%s)', error_status, id, msg) if block: block.err_no = error_status @@ -516,7 +515,7 @@ class Log(): if (cmd == CMD_STOP_LOGGING): if (error_status == 0x00): - logger.info("Have successfully stopped logging for id=%d", + logger.info('Have successfully stopped logging for id=%d', id) if block: block.started = False @@ -525,7 +524,7 @@ class Log(): # Accept deletion of a block that isn't added. This could # happen due to timing (i.e add/start/delete in fast sequence) if error_status == 0x00 or error_status == errno.ENOENT: - logger.info("Have successfully deleted id=%d", id) + logger.info('Have successfully deleted id=%d', id) if block: block.started = False block.added = False @@ -533,7 +532,7 @@ class Log(): if (cmd == CMD_RESET_LOGGING): # Guard against multiple responses due to re-sending if not self.toc: - logger.debug("Logging reset, continue with TOC download") + logger.debug('Logging reset, continue with TOC download') self.log_blocks = [] self.toc = Toc() @@ -547,11 +546,11 @@ class Log(): chan = packet.channel id = packet.data[0] block = self._find_block(id) - timestamps = struct.unpack("<BBB", packet.data[1:4]) + timestamps = struct.unpack('<BBB', packet.data[1:4]) timestamp = ( timestamps[0] | timestamps[1] << 8 | timestamps[2] << 16) logdata = packet.data[4:] if (block is not None): block.unpack_log_data(logdata, timestamp) else: - logger.warning("Error no LogEntry to handle id=%d", id) + logger.warning('Error no LogEntry to handle id=%d', id) diff --git a/cflib/crazyflie/mem.py b/cflib/crazyflie/mem.py index 7aae03b614dab8df79a927d9a81179e9ebef865f..ebd370422f4643f893aa80ffe650057f1f1769e1 100644 --- a/cflib/crazyflie/mem.py +++ b/cflib/crazyflie/mem.py @@ -20,27 +20,25 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Enables flash access to the Crazyflie. """ - -import struct import errno +import logging +import struct import sys -from threading import Lock -from cflib.crtp.crtpstack import CRTPPacket, CRTPPort -from cflib.utils.callbacks import Caller from binascii import crc32 -import binascii -import logging from functools import reduce +from threading import Lock + +from cflib.crtp.crtpstack import CRTPPacket +from cflib.crtp.crtpstack import CRTPPort +from cflib.utils.callbacks import Caller __author__ = 'Bitcraze AB' __all__ = ['Memory', 'MemoryElement'] @@ -59,9 +57,9 @@ CMD_INFO_DETAILS = 2 MAX_LOG_DATA_PACKET_SIZE = 30 if sys.version_info < (3,): - EEPROM_TOKEN = "0xBC" + EEPROM_TOKEN = '0xBC' else: - EEPROM_TOKEN = b"0xBC" + EEPROM_TOKEN = b'0xBC' logger = logging.getLogger(__name__) @@ -84,19 +82,19 @@ class MemoryElement(object): def type_to_string(t): """Get string representation of memory type""" if t == MemoryElement.TYPE_I2C: - return "I2C" + return 'I2C' if t == MemoryElement.TYPE_1W: - return "1-wire" + return '1-wire' if t == MemoryElement.TYPE_DRIVER_LED: - return "LED driver" - return "Unknown" + return 'LED driver' + return 'Unknown' def new_data(self, mem, addr, data): - logger.info("New data, but not OW mem") + logger.info('New data, but not OW mem') def __str__(self): """Generate debug string for memory""" - return ("Memory: id={}, type={}, size={}".format( + return ('Memory: id={}, type={}, size={}'.format( self.id, MemoryElement.type_to_string(self.type), self.size)) @@ -164,13 +162,13 @@ class LEDDriverMemory(MemoryElement): if not self._update_finished_cb: self._update_finished_cb = update_finished_cb self.valid = False - logger.info("Updating content of memory {}".format(self.id)) + logger.info('Updating content of memory {}'.format(self.id)) # Start reading the header self.mem_handler.read(self, 0, 16) def write_done(self, mem, addr): if self._write_finished_cb and mem.id == self.id: - logger.info("Write to LED driver done") + logger.info('Write to LED driver done') self._write_finished_cb(self, addr) self._write_finished_cb = None @@ -180,6 +178,7 @@ class LEDDriverMemory(MemoryElement): class I2CElement(MemoryElement): + def __init__(self, id, type, size, mem_handler): super(I2CElement, self).__init__(id=id, type=type, size=size, mem_handler=mem_handler) @@ -195,28 +194,28 @@ class I2CElement(MemoryElement): done = False # Check for header if data[0:4] == EEPROM_TOKEN: - logger.info("Got new data: {}".format(data)) - [self.elements["version"], - self.elements["radio_channel"], - self.elements["radio_speed"], - self.elements["pitch_trim"], - self.elements["roll_trim"]] = struct.unpack("<BBBff", + logger.info('Got new data: {}'.format(data)) + [self.elements['version'], + self.elements['radio_channel'], + self.elements['radio_speed'], + self.elements['pitch_trim'], + self.elements['roll_trim']] = struct.unpack('<BBBff', data[4:15]) - if self.elements["version"] == 0: + if self.elements['version'] == 0: done = True - elif self.elements["version"] == 1: + elif self.elements['version'] == 1: self.datav0 = data self.mem_handler.read(self, 16, 5) else: - valid = False + self.valid = False if self._update_finished_cb: self._update_finished_cb(self) self._update_finished_cb = None if addr == 16: [radio_address_upper, radio_address_lower] = struct.unpack( - "<BI", self.datav0[15:16] + data[0:4]) - self.elements["radio_address"] = int( + '<BI', self.datav0[15:16] + data[0:4]) + self.elements['radio_address'] = int( radio_address_upper) << 32 | radio_address_lower logger.info(self.elements) @@ -236,35 +235,35 @@ class I2CElement(MemoryElement): def write_data(self, write_finished_cb): image = bytearray() - if self.elements["version"] == 0: + if self.elements['version'] == 0: data = ( - 0x00, self.elements["radio_channel"], - self.elements["radio_speed"], - self.elements["pitch_trim"], self.elements["roll_trim"]) - image += struct.pack("<BBBff", *data) - elif self.elements["version"] == 1: + 0x00, self.elements['radio_channel'], + self.elements['radio_speed'], + self.elements['pitch_trim'], self.elements['roll_trim']) + image += struct.pack('<BBBff', *data) + elif self.elements['version'] == 1: data = ( - 0x01, self.elements["radio_channel"], - self.elements["radio_speed"], - self.elements["pitch_trim"], self.elements["roll_trim"], - self.elements["radio_address"] >> 32, - self.elements["radio_address"] & 0xFFFFFFFF) - image += struct.pack("<BBBffBI", *data) + 0x01, self.elements['radio_channel'], + self.elements['radio_speed'], + self.elements['pitch_trim'], self.elements['roll_trim'], + self.elements['radio_address'] >> 32, + self.elements['radio_address'] & 0xFFFFFFFF) + image += struct.pack('<BBBffBI', *data) # Adding some magic: image = EEPROM_TOKEN + image - image += struct.pack("B", self._checksum256(image)) + image += struct.pack('B', self._checksum256(image)) self._write_finished_cb = write_finished_cb self.mem_handler.write(self, 0x00, - struct.unpack("B" * len(image), image)) + struct.unpack('B' * len(image), image)) def update(self, update_finished_cb): """Request an update of the memory content""" if not self._update_finished_cb: self._update_finished_cb = update_finished_cb self.valid = False - logger.info("Updating content of memory {}".format(self.id)) + logger.info('Updating content of memory {}'.format(self.id)) # Start reading the header self.mem_handler.read(self, 0, 16) @@ -282,9 +281,9 @@ class OWElement(MemoryElement): """Memory class with extra functionality for 1-wire memories""" element_mapping = { - 1: "Board name", - 2: "Board revision", - 3: "Custom" + 1: 'Board name', + 2: 'Board revision', + 3: 'Custom' } def __init__(self, id, type, size, addr, mem_handler): @@ -319,7 +318,7 @@ class OWElement(MemoryElement): self._update_finished_cb = None else: # We need to fetch the elements, find out the length - (elem_ver, elem_len) = struct.unpack("BB", data[8:10]) + (elem_ver, elem_len) = struct.unpack('BB', data[8:10]) self.mem_handler.read(self, 8, elem_len + 3) else: # Call the update if the CRC check of the header fails, @@ -338,14 +337,14 @@ class OWElement(MemoryElement): """ Parse and check the CRC and length of the elements part of the memory """ - (elem_ver, elem_len, crc) = (data[0], data[1], data[-1]) + crc = data[-1] test_crc = crc32(data[:-1]) & 0x0ff elem_data = data[2:-1] if test_crc == crc: while len(elem_data) > 0: - (eid, elen) = struct.unpack("BB", elem_data[:2]) + (eid, elen) = struct.unpack('BB', elem_data[:2]) self.elements[self.element_mapping[eid]] = \ - elem_data[2:2 + elen].decode("ISO-8859-1") + elem_data[2:2 + elen].decode('ISO-8859-1') elem_data = elem_data[2 + elen:] return True return False @@ -357,9 +356,9 @@ class OWElement(MemoryElement): def write_data(self, write_finished_cb): # First generate the header part - header_data = struct.pack("<BIBB", 0xEB, self.pins, self.vid, self.pid) + header_data = struct.pack('<BIBB', 0xEB, self.pins, self.vid, self.pid) header_crc = crc32(header_data) & 0x0ff - header_data += struct.pack("B", header_crc) + header_data += struct.pack('B', header_crc) # Now generate the elements part elem = bytearray() @@ -368,18 +367,18 @@ class OWElement(MemoryElement): elem_string = self.elements[element] # logger.info(">>>> {}".format(elem_string)) key_encoding = self._rev_element_mapping[element] - elem += struct.pack("BB", key_encoding, len(elem_string)) - elem += bytearray(elem_string.encode("ISO-8859-1")) + elem += struct.pack('BB', key_encoding, len(elem_string)) + elem += bytearray(elem_string.encode('ISO-8859-1')) - elem_data = struct.pack("BB", 0x00, len(elem)) + elem_data = struct.pack('BB', 0x00, len(elem)) elem_data += elem elem_crc = crc32(elem_data) & 0x0ff - elem_data += struct.pack("B", elem_crc) + elem_data += struct.pack('B', elem_crc) data = header_data + elem_data self.mem_handler.write(self, 0x00, - struct.unpack("B" * len(data), data)) + struct.unpack('B' * len(data), data)) self._write_finished_cb = write_finished_cb @@ -388,14 +387,14 @@ class OWElement(MemoryElement): if not self._update_finished_cb: self._update_finished_cb = update_finished_cb self.valid = False - logger.info("Updating content of memory {}".format(self.id)) + logger.info('Updating content of memory {}'.format(self.id)) # Start reading the header self.mem_handler.read(self, 0, 11) def _parse_and_check_header(self, data): """Parse and check the CRC of the header part of the memory""" # logger.info("Should parse header: {}".format(data)) - (start, self.pins, self.vid, self.pid, crc) = struct.unpack("<BIBBB", + (start, self.pins, self.vid, self.pid, crc) = struct.unpack('<BIBBB', data) test_crc = crc32(data[:-1]) & 0x0ff if start == 0xEB and crc == test_crc: @@ -404,7 +403,7 @@ class OWElement(MemoryElement): def __str__(self): """Generate debug string for memory""" - return ("OW {} ({:02X}:{:02X}): {}".format( + return ('OW {} ({:02X}:{:02X}): {}'.format( self.addr, self.vid, self.pid, self.elements)) def disconnect(self): @@ -434,7 +433,7 @@ class _ReadRequest: self._request_new_chunk() def resend(self): - logger.info("Sending write again...") + logger.info('Sending write again...') self._request_new_chunk() def _request_new_chunk(self): @@ -446,14 +445,14 @@ class _ReadRequest: if new_len > _ReadRequest.MAX_DATA_LENGTH: new_len = _ReadRequest.MAX_DATA_LENGTH - logger.info("Requesting new chunk of {}bytes at 0x{:X}".format( + logger.info('Requesting new chunk of {}bytes at 0x{:X}'.format( new_len, self._current_addr)) # Request the data for the next address pk = CRTPPacket() pk.set_header(CRTPPort.MEM, CHAN_READ) - pk.data = struct.pack("<BIB", self.mem.id, self._current_addr, new_len) - reply = struct.unpack("<BBBBB", pk.data[:-1]) + pk.data = struct.pack('<BIB', self.mem.id, self._current_addr, new_len) + reply = struct.unpack('<BBBBB', pk.data[:-1]) self.cf.send_packet(pk, expected_reply=reply, timeout=1) def add_data(self, addr, data): @@ -461,7 +460,7 @@ class _ReadRequest: data_len = len(data) if not addr == self._current_addr: logger.warning( - "Address did not match when adding data to read request!") + 'Address did not match when adding data to read request!') return # Add the data and calculate the next address to fetch @@ -504,7 +503,7 @@ class _WriteRequest: self._write_new_chunk() def resend(self): - logger.info("Sending write again...") + logger.info('Sending write again...') self.cf.send_packet( self._sent_packet, expected_reply=self._sent_reply, timeout=1) @@ -517,7 +516,7 @@ class _WriteRequest: if new_len > _WriteRequest.MAX_DATA_LENGTH: new_len = _WriteRequest.MAX_DATA_LENGTH - logger.info("Writing new chunk of {}bytes at 0x{:X}".format( + logger.info('Writing new chunk of {}bytes at 0x{:X}'.format( new_len, self._current_addr)) data = self._data[:new_len] @@ -525,12 +524,12 @@ class _WriteRequest: pk = CRTPPacket() pk.set_header(CRTPPort.MEM, CHAN_WRITE) - pk.data = struct.pack("<BI", self.mem.id, self._current_addr) + pk.data = struct.pack('<BI', self.mem.id, self._current_addr) # Create a tuple used for matching the reply using id and address - reply = struct.unpack("<BBBBB", pk.data) + reply = struct.unpack('<BBBBB', pk.data) self._sent_reply = reply # Add the data - pk.data += struct.pack("B" * len(data), *data) + pk.data += struct.pack('B' * len(data), *data) self._sent_packet = pk self.cf.send_packet(pk, expected_reply=reply, timeout=1) @@ -540,7 +539,7 @@ class _WriteRequest: """Callback when data is received from the Crazyflie""" if not addr == self._current_addr: logger.warning( - "Address did not match when adding data to read request!") + 'Address did not match when adding data to read request!') return if len(self._data) > 0: @@ -548,7 +547,7 @@ class _WriteRequest: self._write_new_chunk() return False else: - logger.info("This write request is done") + logger.info('This write request is done') return True @@ -559,11 +558,11 @@ class Memory(): # some of the text messages will look very strange # in the UI, so they are redefined here _err_codes = { - errno.ENOMEM: "No more memory available", - errno.ENOEXEC: "Command not found", - errno.ENOENT: "No such block id", - errno.E2BIG: "Block too large", - errno.EEXIST: "Block already exists" + errno.ENOMEM: 'No more memory available', + errno.ENOEXEC: 'Command not found', + errno.ENOENT: 'No such block id', + errno.E2BIG: 'Block too large', + errno.EEXIST: 'Block already exists' } def __init__(self, crazyflie=None): @@ -657,8 +656,8 @@ class Memory(): address """ if memory.id in self._read_requests: - logger.warning("There is already a read operation ongoing for " - "memory id {}".format(memory.id)) + logger.warning('There is already a read operation ongoing for ' + 'memory id {}'.format(memory.id)) return False rreq = _ReadRequest(memory, addr, length, self.cf) @@ -678,13 +677,13 @@ class Memory(): m.disconnect() except Exception as e: logger.info( - "Error when removing memory after update: {}".format(e)) + 'Error when removing memory after update: {}'.format(e)) self.mems = [] self.nbr_of_mems = 0 self._getting_count = False - logger.info("Requesting number of memories") + logger.info('Requesting number of memories') pk = CRTPPacket() pk.set_header(CRTPPort.MEM, CHAN_INFO) pk.data = (CMD_INFO_NBR,) @@ -699,14 +698,14 @@ class Memory(): if chan == CHAN_INFO: if cmd == CMD_INFO_NBR: self.nbr_of_mems = payload[0] - logger.info("{} memories found".format(self.nbr_of_mems)) + logger.info('{} memories found'.format(self.nbr_of_mems)) # Start requesting information about the memories, # if there are any... if self.nbr_of_mems > 0: if not self._getting_count: self._getting_count = True - logger.info("Requesting first id") + logger.info('Requesting first id') pk = CRTPPacket() pk.set_header(CRTPPort.MEM, CHAN_INFO) pk.data = (CMD_INFO_DETAILS, 0) @@ -724,7 +723,7 @@ class Memory(): # the 1-wire. Fail by saying we only found 1 memory # (the I2C). logger.error( - "-------->Got good count, but no info on mem!") + '-------->Got good count, but no info on mem!') self.nbr_of_mems = 1 if self._refresh_callback: self._refresh_callback() @@ -737,12 +736,12 @@ class Memory(): # Type - 1 byte mem_type = payload[1] # Size 4 bytes (as addr) - mem_size = struct.unpack("I", payload[2:6])[0] + mem_size = struct.unpack('I', payload[2:6])[0] # Addr (only valid for 1-wire?) - mem_addr_raw = struct.unpack("B" * 8, payload[6:14]) - mem_addr = "" + mem_addr_raw = struct.unpack('B' * 8, payload[6:14]) + mem_addr = '' for m in mem_addr_raw: - mem_addr += "{:02X}".format(m) + mem_addr += '{:02X}'.format(m) if (not self.get_mem(mem_id)): if mem_type == MemoryElement.TYPE_1W: @@ -776,7 +775,7 @@ class Memory(): if self.nbr_of_mems - 1 >= self._fetch_id: logger.info( - "Requesting information about memory {}".format( + 'Requesting information about memory {}'.format( self._fetch_id)) pk = CRTPPacket() pk.set_header(CRTPPort.MEM, CHAN_INFO) @@ -785,22 +784,22 @@ class Memory(): CMD_INFO_DETAILS, self._fetch_id)) else: logger.info( - "Done getting all the memories, start reading the OWs") + 'Done getting all the memories, start reading the OWs') ows = self.get_mems(MemoryElement.TYPE_1W) # If there are any OW mems start reading them, otherwise # we are done - for ow_mem in self.get_mems(MemoryElement.TYPE_1W): + for ow_mem in ows: ow_mem.update(self._mem_update_done) - if len(self.get_mems(MemoryElement.TYPE_1W)) == 0: + if len(ows) == 0: if self._refresh_callback: self._refresh_callback() self._refresh_callback = None if chan == CHAN_WRITE: id = cmd - (addr, status) = struct.unpack("<IB", payload[0:5]) + (addr, status) = struct.unpack('<IB', payload[0:5]) logger.info( - "WRITE: Mem={}, addr=0x{:X}, status=0x{}".format( + 'WRITE: Mem={}, addr=0x{:X}, status=0x{}'.format( id, addr, status)) # Find the read request if id in self._write_requests: @@ -818,26 +817,26 @@ class Memory(): self._write_requests[id][0].start() else: - logger.info("Status {}: write resending...".format(status)) + logger.info('Status {}: write resending...'.format(status)) wreq.resend() self._write_requests_lock.release() if chan == CHAN_READ: id = cmd - (addr, status) = struct.unpack("<IB", payload[0:5]) - data = struct.unpack("B" * len(payload[5:]), payload[5:]) - logger.info("READ: Mem={}, addr=0x{:X}, status=0x{}, " - "data={}".format(id, addr, status, data)) + (addr, status) = struct.unpack('<IB', payload[0:5]) + data = struct.unpack('B' * len(payload[5:]), payload[5:]) + logger.info('READ: Mem={}, addr=0x{:X}, status=0x{}, ' + 'data={}'.format(id, addr, status, data)) # Find the read request if id in self._read_requests: logger.info( - "READING: We are still interested in request for " - "mem {}".format(id)) + 'READING: We are still interested in request for ' + 'mem {}'.format(id)) rreq = self._read_requests[id] if status == 0: if rreq.add_data(addr, payload[5:]): self._read_requests.pop(id, None) self.mem_read_cb.call(rreq.mem, rreq.addr, rreq.data) else: - logger.info("Status {}: resending...".format(status)) + logger.info('Status {}: resending...'.format(status)) rreq.resend() diff --git a/cflib/crazyflie/param.py b/cflib/crazyflie/param.py index 8dc77ca711d236da02bb51e6b6252570f8017c32..1f43e17813f3d524aa7eaca765b2ff49f016d853 100644 --- a/cflib/crazyflie/param.py +++ b/cflib/crazyflie/param.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Enables reading/writing of parameter values to/from the Crazyflie. @@ -33,14 +31,17 @@ When a Crazyflie is connected it's possible to download a TableOfContent of all the parameters that can be written/read. """ - -from cflib.utils.callbacks import Caller +import logging import struct -from cflib.crtp.crtpstack import CRTPPacket, CRTPPort -from .toc import Toc, TocFetcher -from threading import Thread, Lock import sys -import logging +from threading import Lock +from threading import Thread + +from .toc import Toc +from .toc import TocFetcher +from cflib.crtp.crtpstack import CRTPPacket +from cflib.crtp.crtpstack import CRTPPort +from cflib.utils.callbacks import Caller if sys.version_info < (3,): from Queue import Queue else: @@ -75,29 +76,29 @@ class ParamTocElement: RW_ACCESS = 0 RO_ACCESS = 1 - types = {0x08: ("uint8_t", '<B'), - 0x09: ("uint16_t", '<H'), - 0x0A: ("uint32_t", '<L'), - 0x0B: ("uint64_t", '<Q'), - 0x00: ("int8_t", '<b'), - 0x01: ("int16_t", '<h'), - 0x02: ("int32_t", '<i'), - 0x03: ("int64_t", '<q'), - 0x05: ("FP16", ''), - 0x06: ("float", '<f'), - 0x07: ("double", '<d')} + types = {0x08: ('uint8_t', '<B'), + 0x09: ('uint16_t', '<H'), + 0x0A: ('uint32_t', '<L'), + 0x0B: ('uint64_t', '<Q'), + 0x00: ('int8_t', '<b'), + 0x01: ('int16_t', '<h'), + 0x02: ('int32_t', '<i'), + 0x03: ('int64_t', '<q'), + 0x05: ('FP16', ''), + 0x06: ('float', '<f'), + 0x07: ('double', '<d')} def __init__(self, data=None): """TocElement creator. Data is the binary payload of the element.""" if (data): - strs = struct.unpack("s" * len(data[2:]), data[2:]) + strs = struct.unpack('s' * len(data[2:]), data[2:]) if sys.version_info < (3,): - strs = ("{}" * len(strs)).format(*strs).split("\0") + strs = ('{}' * len(strs)).format(*strs).split('\0') else: - s = "" + s = '' for ch in strs: s += ch.decode('ISO-8859-1') - strs = s.split("\x00") + strs = s.split('\x00') self.group = strs[0] self.name = strs[1] @@ -119,8 +120,8 @@ class ParamTocElement: def get_readable_access(self): if (self.access == ParamTocElement.RO_ACCESS): - return "RO" - return "RW" + return 'RO' + return 'RW' class Param(): @@ -151,7 +152,7 @@ class Param(): """Request an update of all the parameters in the TOC""" for group in self.toc.toc: for name in self.toc.toc[group]: - complete_name = "%s.%s" % (group, name) + complete_name = '%s.%s' % (group, name) self.request_param_update(complete_name) def _check_if_all_updated(self): @@ -173,14 +174,14 @@ class Param(): if element: s = struct.unpack(element.pytype, pk.data[1:])[0] s = s.__str__() - complete_name = "%s.%s" % (element.group, element.name) + complete_name = '%s.%s' % (element.group, element.name) # Save the value for synchronous access if element.group not in self.values: self.values[element.group] = {} self.values[element.group][element.name] = s - logger.debug("Updated parameter [%s]" % complete_name) + logger.debug('Updated parameter [%s]' % complete_name) if complete_name in self.param_update_callbacks: self.param_update_callbacks[complete_name].call( complete_name, s) @@ -196,7 +197,7 @@ class Param(): self.is_updated = True self.all_updated.call() else: - logger.debug("Variable id [%d] not found in TOC", var_id) + logger.debug('Variable id [%d] not found in TOC', var_id) def remove_update_callback(self, group, name=None, cb=None): """Remove the supplied callback for a group or a group.name""" @@ -207,7 +208,7 @@ class Param(): if group in self.group_update_callbacks: self.group_update_callbacks[group].remove_callback(cb) else: - paramname = "{}.{}".format(group, name) + paramname = '{}.{}'.format(group, name) if paramname in self.param_update_callbacks: self.param_update_callbacks[paramname].remove_callback(cb) @@ -223,7 +224,7 @@ class Param(): self.group_update_callbacks[group] = Caller() self.group_update_callbacks[group].add_callback(cb) else: - paramname = "{}.{}".format(group, name) + paramname = '{}.{}'.format(group, name) if paramname not in self.param_update_callbacks: self.param_update_callbacks[paramname] = Caller() self.param_update_callbacks[paramname].add_callback(cb) @@ -261,11 +262,11 @@ class Param(): if not element: logger.warning("Cannot set value for [%s], it's not in the TOC!", complete_name) - raise KeyError("{} not in param TOC".format(complete_name)) + raise KeyError('{} not in param TOC'.format(complete_name)) elif element.access == ParamTocElement.RO_ACCESS: - logger.debug("[%s] is read only, no trying to set value", + logger.debug('[%s] is read only, no trying to set value', complete_name) - raise AttributeError("{} is read-only!".format(complete_name)) + raise AttributeError('{} is read-only!'.format(complete_name)) else: varid = element.ident pk = CRTPPacket() @@ -325,7 +326,7 @@ class _ParamUpdater(Thread): pk = CRTPPacket() pk.set_header(CRTPPort.PARAM, READ_CHANNEL) pk.data = struct.pack('<B', var_id) - logger.debug("Requesting request to update param [%d]", var_id) + logger.debug('Requesting request to update param [%d]', var_id) self.request_queue.put(pk) def run(self): diff --git a/cflib/crazyflie/platformservice.py b/cflib/crazyflie/platformservice.py index 10abdc252ad9c5c32433b155fdbdbc470cb53e8e..ad922db13f9ccba6347dedf46902ffaa31b1ed81 100644 --- a/cflib/crazyflie/platformservice.py +++ b/cflib/crazyflie/platformservice.py @@ -20,18 +20,15 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Used for sending control setpoints to the Crazyflie """ - -from cflib.crtp.crtpstack import CRTPPacket, CRTPPort -import struct +from cflib.crtp.crtpstack import CRTPPacket +from cflib.crtp.crtpstack import CRTPPort __author__ = 'Bitcraze AB' __all__ = ['PlatformService'] diff --git a/cflib/crazyflie/toc.py b/cflib/crazyflie/toc.py index 984e93ebaaf5d528ee4f1f102ad8c68b17fa434f..54097aba67b4a5de2428762f458e03c0ad04340b 100644 --- a/cflib/crazyflie/toc.py +++ b/cflib/crazyflie/toc.py @@ -20,21 +20,18 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ A generic TableOfContents module that is used to fetch, store and minipulate a TOC for logging or parameters. """ - -from cflib.crtp.crtpstack import CRTPPacket +import logging import struct -import logging +from cflib.crtp.crtpstack import CRTPPacket __author__ = 'Bitcraze AB' __all__ = ['TocElement', 'Toc', 'TocFetcher'] @@ -48,9 +45,9 @@ CMD_TOC_ELEMENT = 0 CMD_TOC_INFO = 1 # Possible states when receiving TOC -IDLE = "IDLE" -GET_TOC_INFO = "GET_TOC_INFO" -GET_TOC_ELEMENT = "GET_TOC_ELEMENT" +IDLE = 'IDLE' +GET_TOC_INFO = 'GET_TOC_INFO' +GET_TOC_ELEMENT = 'GET_TOC_ELEMENT' class TocElement: @@ -59,10 +56,10 @@ class TocElement: RO_ACCESS = 1 ident = 0 - group = "" - name = "" - ctype = "" - pytype = "" + group = '' + name = '' + ctype = '' + pytype = '' access = RO_ACCESS @@ -96,12 +93,12 @@ class Toc: def get_element_id(self, complete_name): """Get the TocElement element id-number of the element with the supplied name.""" - [group, name] = complete_name.split(".") + [group, name] = complete_name.split('.') element = self.get_element(group, name) if element: return element.ident else: - logger.warning("Unable to find variable [%s]", complete_name) + logger.warning('Unable to find variable [%s]', complete_name) return None def get_element(self, group, name): @@ -140,7 +137,7 @@ class TocFetcher: def start(self): """Initiate fetching of the TOC.""" - logger.debug("[%d]: Start fetching...", self.port) + logger.debug('[%d]: Start fetching...', self.port) # Register callback in this class for the port self.cf.add_port_callback(self.port, self._new_packet_cb) @@ -154,7 +151,7 @@ class TocFetcher: def _toc_fetch_finished(self): """Callback for when the TOC fetching is finished""" self.cf.remove_port_callback(self.port, self._new_packet_cb) - logger.debug("[%d]: Done!", self.port) + logger.debug('[%d]: Done!', self.port) self.finished_callback() def _new_packet_cb(self, packet): @@ -165,14 +162,14 @@ class TocFetcher: payload = packet.data[1:] if (self.state == GET_TOC_INFO): - [self.nbr_of_items, self._crc] = struct.unpack("<BI", payload[:5]) - logger.debug("[%d]: Got TOC CRC, %d items and crc=0x%08X", + [self.nbr_of_items, self._crc] = struct.unpack('<BI', payload[:5]) + logger.debug('[%d]: Got TOC CRC, %d items and crc=0x%08X', self.port, self.nbr_of_items, self._crc) cache_data = self._toc_cache.fetch(self._crc) if (cache_data): self.toc.toc = cache_data - logger.info("TOC for port [%s] found in cache" % self.port) + logger.info('TOC for port [%s] found in cache' % self.port) self._toc_fetch_finished() else: self.state = GET_TOC_ELEMENT @@ -185,10 +182,10 @@ class TocFetcher: if self.requested_index != payload[0]: return self.toc.add_element(self.element_class(payload)) - logger.debug("Added element [%s]", + logger.debug('Added element [%s]', self.element_class(payload).ident) if (self.requested_index < (self.nbr_of_items - 1)): - logger.debug("[%d]: More variables, requesting index %d", + logger.debug('[%d]: More variables, requesting index %d', self.port, self.requested_index + 1) self.requested_index = self.requested_index + 1 self._request_toc_element(self.requested_index) @@ -198,7 +195,7 @@ class TocFetcher: def _request_toc_element(self, index): """Request information about a specific item in the TOC""" - logger.debug("Requesting index %d on port %d", index, self.port) + logger.debug('Requesting index %d on port %d', index, self.port) pk = CRTPPacket() pk.set_header(self.port, TOC_CHANNEL) pk.data = (CMD_TOC_ELEMENT, index) diff --git a/cflib/crazyflie/toccache.py b/cflib/crazyflie/toccache.py index 22add3c8ea979e3e9352badd2ca5f77b5026cda7..74bb9591b352351dffaee1d0670d71bedbc3a972 100644 --- a/cflib/crazyflie/toccache.py +++ b/cflib/crazyflie/toccache.py @@ -20,22 +20,18 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Access the TOC cache for reading/writing. It supports both user cache and dist cache. """ - -import os import json -from glob import glob - import logging +import os +from glob import glob from .log import LogTocElement # pylint: disable=W0611 from .param import ParamTocElement # pylint: disable=W0611 @@ -55,9 +51,9 @@ class TocCache(): def __init__(self, ro_cache=None, rw_cache=None): self._cache_files = [] if (ro_cache): - self._cache_files += glob(ro_cache + "/*.json") + self._cache_files += glob(ro_cache + '/*.json') if (rw_cache): - self._cache_files += glob(rw_cache + "/*.json") + self._cache_files += glob(rw_cache + '/*.json') if not os.path.exists(rw_cache): os.makedirs(rw_cache) @@ -66,7 +62,7 @@ class TocCache(): def fetch(self, crc): """ Try to get a hit in the cache, return None otherwise """ cache_data = None - pattern = "%08X.json" % crc + pattern = '%08X.json' % crc hit = None for name in self._cache_files: @@ -80,7 +76,7 @@ class TocCache(): object_hook=self._decoder) cache.close() except Exception as exp: - logger.warning("Error while parsing cache file [%s]:%s", + logger.warning('Error while parsing cache file [%s]:%s', hit, str(exp)) return cache_data @@ -89,18 +85,18 @@ class TocCache(): """ Save a new cache to file """ if self._rw_cache: try: - filename = "%s/%08X.json" % (self._rw_cache, crc) + filename = '%s/%08X.json' % (self._rw_cache, crc) cache = open(filename, 'w') cache.write(json.dumps(toc, indent=2, default=self._encoder)) cache.close() - logger.info("Saved cache to [%s]", filename) + logger.info('Saved cache to [%s]', filename) self._cache_files += [filename] except Exception as exp: - logger.warning("Could not save cache to file [%s]: %s", + logger.warning('Could not save cache to file [%s]: %s', filename, str(exp)) else: - logger.warning("Could not save cache, no writable directory") + logger.warning('Could not save cache, no writable directory') def _encoder(self, obj): """ Encode a toc element leaf-node """ diff --git a/cflib/crtp/__init__.py b/cflib/crtp/__init__.py index 0624614b03b043d1bf3a5a72b5945c23578f330e..970c53f73016b51c2a622e76b7ece3102b12fb67 100644 --- a/cflib/crtp/__init__.py +++ b/cflib/crtp/__init__.py @@ -20,22 +20,19 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """Scans and creates communication interfaces.""" - import logging +from .debugdriver import DebugDriver +from .exceptions import WrongUriType from .radiodriver import RadioDriver -from .udpdriver import UdpDriver from .serialdriver import SerialDriver -from .debugdriver import DebugDriver +from .udpdriver import UdpDriver from .usbdriver import UsbDriver -from .exceptions import WrongUriType __author__ = 'Bitcraze AB' __all__ = [] @@ -62,7 +59,7 @@ def scan_interfaces(address=None): available = [] found = [] for instance in INSTANCES: - logger.debug("Scanning: %s", instance) + logger.debug('Scanning: %s', instance) try: found = instance.scan_interface(address) available += found diff --git a/cflib/crtp/crtpdriver.py b/cflib/crtp/crtpdriver.py index 246f8d3ed0130dfbbadeee4dadd435ed0c1e091c..7d9f7d8cb966a40bba79a984af67e2f3736c3aa8 100644 --- a/cflib/crtp/crtpdriver.py +++ b/cflib/crtp/crtpdriver.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ CRTP Driver main class. """ diff --git a/cflib/crtp/crtpstack.py b/cflib/crtp/crtpstack.py index dc46ccd5209552bddf06a18e21219e7865c14be9..6bfe0347b60d34c6da531eb9a53fa84dbc8cdc04 100644 --- a/cflib/crtp/crtpstack.py +++ b/cflib/crtp/crtpstack.py @@ -20,18 +20,15 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ CRTP packet and ports. """ - -import sys import logging +import sys __author__ = 'Bitcraze AB' __all__ = ['CRTPPort', 'CRTPPacket'] @@ -129,8 +126,8 @@ class CRTPPacket(object): elif sys.version_info >= (3,) and type(data) == bytes: self._data = bytearray(data) else: - raise Exception("Data must be bytearray, string, list or tuple," - " not {}".format(type(data))) + raise Exception('Data must be bytearray, string, list or tuple,' + ' not {}'.format(type(data))) def _get_data_l(self): """Get the data in the packet as a list""" @@ -142,7 +139,7 @@ class CRTPPacket(object): def __str__(self): """Get a string representation of the packet""" - return "{}:{} {}".format(self._port, self.channel, self.datat) + return '{}:{} {}'.format(self._port, self.channel, self.datat) data = property(_get_data, _set_data) datal = property(_get_data_l, _set_data) diff --git a/cflib/crtp/debugdriver.py b/cflib/crtp/debugdriver.py index 4bfcc5da6f8f9b8c8158c1cd1f4e042102e8a06e..d734e933c19727960cc6973f776fd04a2af50c8d 100644 --- a/cflib/crtp/debugdriver.py +++ b/cflib/crtp/debugdriver.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Fake link driver used to debug the UI without using the Crazyflie. @@ -36,23 +34,23 @@ though CRTP once connected. For normal connections a console thread is also started that will send generated console output via CRTP. """ - -from threading import Thread -from .crtpdriver import CRTPDriver -from .crtpstack import CRTPPacket, CRTPPort -from .exceptions import WrongUriType -import sys +import errno +import logging +import random import re -import time +import string import struct +import sys +import time from datetime import datetime +from threading import Thread + +from .crtpdriver import CRTPDriver +from .crtpstack import CRTPPacket +from .crtpstack import CRTPPort +from .exceptions import WrongUriType from cflib.crazyflie.log import LogTocElement from cflib.crazyflie.param import ParamTocElement -import random -import string -import errno - -import logging if sys.version_info < (3,): import Queue as queue else: @@ -64,13 +62,13 @@ __all__ = ['DebugDriver'] logger = logging.getLogger(__name__) # This setup is used to debug raw memory logging -memlogging = {0x01: {"min": 0, "max": 255, "mod": 1, "vartype": 1}, - 0x02: {"min": 0, "max": 65000, "mod": 100, "vartype": 2}, - 0x03: {"min": 0, "max": 100000, "mod": 1000, "vartype": 3}, - 0x04: {"min": -100, "max": 100, "mod": 1, "vartype": 4}, - 0x05: {"min": -10000, "max": 10000, "mod": 2000, "vartype": 5}, - 0x06: {"min": -50000, "max": 50000, "mod": 1000, "vartype": 6}, - 0x07: {"min": 0, "max": 255, "mod": 1, "vartype": 1}} +memlogging = {0x01: {'min': 0, 'max': 255, 'mod': 1, 'vartype': 1}, + 0x02: {'min': 0, 'max': 65000, 'mod': 100, 'vartype': 2}, + 0x03: {'min': 0, 'max': 100000, 'mod': 1000, 'vartype': 3}, + 0x04: {'min': -100, 'max': 100, 'mod': 1, 'vartype': 4}, + 0x05: {'min': -10000, 'max': 10000, 'mod': 2000, 'vartype': 5}, + 0x06: {'min': -50000, 'max': 50000, 'mod': 1000, 'vartype': 6}, + 0x07: {'min': 0, 'max': 255, 'mod': 1, 'vartype': 1}} class FakeMemory: @@ -100,180 +98,180 @@ class DebugDriver(CRTPDriver): self.needs_resending = False # Fill up the fake logging TOC with values and data self.fakeLogToc = [] - self.fakeLogToc.append({"varid": 0, "vartype": 5, "vargroup": "imu", - "varname": "gyro_x", "min": -10000, - "max": 10000, "mod": 1000}) - self.fakeLogToc.append({"varid": 1, "vartype": 5, "vargroup": "imu", - "varname": "gyro_y", "min": -10000, - "max": 10000, "mod": 150}) - self.fakeLogToc.append({"varid": 2, "vartype": 5, "vargroup": "imu", - "varname": "gyro_z", "min": -10000, - "max": 10000, "mod": 200}) - self.fakeLogToc.append({"varid": 3, "vartype": 5, "vargroup": "imu", - "varname": "acc_x", "min": -1000, - "max": 1000, "mod": 15}) - self.fakeLogToc.append({"varid": 4, "vartype": 5, "vargroup": "imu", - "varname": "acc_y", "min": -1000, - "max": 1000, "mod": 10}) - self.fakeLogToc.append({"varid": 5, "vartype": 5, "vargroup": "imu", - "varname": "acc_z", "min": -1000, - "max": 1000, "mod": 20}) - self.fakeLogToc.append({"varid": 6, "vartype": 7, - "vargroup": "stabilizer", "varname": "roll", - "min": -90, "max": 90, "mod": 2}) - self.fakeLogToc.append({"varid": 7, "vartype": 7, - "vargroup": "stabilizer", "varname": "pitch", - "min": -90, "max": 90, "mod": 1.5}) - self.fakeLogToc.append({"varid": 8, "vartype": 7, - "vargroup": "stabilizer", "varname": "yaw", - "min": -90, "max": 90, "mod": 2.5}) - self.fakeLogToc.append({"varid": 9, "vartype": 7, "vargroup": "pm", - "varname": "vbat", "min": 3.0, - "max": 4.2, "mod": 0.1}) - self.fakeLogToc.append({"varid": 10, "vartype": 6, "vargroup": "motor", - "varname": "m1", "min": 0, "max": 65000, - "mod": 1000}) - self.fakeLogToc.append({"varid": 11, "vartype": 6, "vargroup": "motor", - "varname": "m2", "min": 0, "max": 65000, - "mod": 1000}) - self.fakeLogToc.append({"varid": 12, "vartype": 6, "vargroup": "motor", - "varname": "m3", "min": 0, "max": 65000, - "mod": 1000}) - self.fakeLogToc.append({"varid": 13, "vartype": 6, "vargroup": "motor", - "varname": "m4", "min": 0, "max": 65000, - "mod": 1000}) - self.fakeLogToc.append({"varid": 14, "vartype": 2, - "vargroup": "stabilizer", "varname": "thrust", - "min": 0, "max": 65000, "mod": 1000}) - self.fakeLogToc.append({"varid": 15, "vartype": 7, - "vargroup": "baro", "varname": "asl", - "min": 540, "max": 545, "mod": 0.5}) - self.fakeLogToc.append({"varid": 16, "vartype": 7, - "vargroup": "baro", "varname": "aslRaw", - "min": 540, "max": 545, "mod": 1.0}) - self.fakeLogToc.append({"varid": 17, "vartype": 7, - "vargroup": "baro", "varname": "aslLong", - "min": 540, "max": 545, "mod": 0.5}) - self.fakeLogToc.append({"varid": 18, "vartype": 7, - "vargroup": "baro", "varname": "temp", - "min": 26, "max": 38, "mod": 1.0}) - self.fakeLogToc.append({"varid": 19, "vartype": 7, - "vargroup": "altHold", "varname": "target", - "min": 542, "max": 543, "mod": 0.1}) - self.fakeLogToc.append({"varid": 20, "vartype": 6, - "vargroup": "gps", "varname": "lat", - "min": 556112190, "max": 556112790, - "mod": 10}) - self.fakeLogToc.append({"varid": 21, "vartype": 6, - "vargroup": "gps", "varname": "lon", - "min": 129945110, "max": 129945710, - "mod": 10}) - self.fakeLogToc.append({"varid": 22, "vartype": 6, - "vargroup": "gps", "varname": "hMSL", - "min": 0, "max": 100000, - "mod": 1000}) - self.fakeLogToc.append({"varid": 23, "vartype": 6, - "vargroup": "gps", "varname": "heading", - "min": -10000000, "max": 10000000, - "mod": 100000}) - self.fakeLogToc.append({"varid": 24, "vartype": 6, - "vargroup": "gps", "varname": "gSpeed", - "min": 0, "max": 1000, - "mod": 100}) - self.fakeLogToc.append({"varid": 25, "vartype": 3, - "vargroup": "gps", "varname": "hAcc", - "min": 0, "max": 5000, - "mod": 100}) - self.fakeLogToc.append({"varid": 26, "vartype": 1, - "vargroup": "gps", "varname": "fixType", - "min": 0, "max": 5, - "mod": 1}) + self.fakeLogToc.append({'varid': 0, 'vartype': 5, 'vargroup': 'imu', + 'varname': 'gyro_x', 'min': -10000, + 'max': 10000, 'mod': 1000}) + self.fakeLogToc.append({'varid': 1, 'vartype': 5, 'vargroup': 'imu', + 'varname': 'gyro_y', 'min': -10000, + 'max': 10000, 'mod': 150}) + self.fakeLogToc.append({'varid': 2, 'vartype': 5, 'vargroup': 'imu', + 'varname': 'gyro_z', 'min': -10000, + 'max': 10000, 'mod': 200}) + self.fakeLogToc.append({'varid': 3, 'vartype': 5, 'vargroup': 'imu', + 'varname': 'acc_x', 'min': -1000, + 'max': 1000, 'mod': 15}) + self.fakeLogToc.append({'varid': 4, 'vartype': 5, 'vargroup': 'imu', + 'varname': 'acc_y', 'min': -1000, + 'max': 1000, 'mod': 10}) + self.fakeLogToc.append({'varid': 5, 'vartype': 5, 'vargroup': 'imu', + 'varname': 'acc_z', 'min': -1000, + 'max': 1000, 'mod': 20}) + self.fakeLogToc.append({'varid': 6, 'vartype': 7, + 'vargroup': 'stabilizer', 'varname': 'roll', + 'min': -90, 'max': 90, 'mod': 2}) + self.fakeLogToc.append({'varid': 7, 'vartype': 7, + 'vargroup': 'stabilizer', 'varname': 'pitch', + 'min': -90, 'max': 90, 'mod': 1.5}) + self.fakeLogToc.append({'varid': 8, 'vartype': 7, + 'vargroup': 'stabilizer', 'varname': 'yaw', + 'min': -90, 'max': 90, 'mod': 2.5}) + self.fakeLogToc.append({'varid': 9, 'vartype': 7, 'vargroup': 'pm', + 'varname': 'vbat', 'min': 3.0, + 'max': 4.2, 'mod': 0.1}) + self.fakeLogToc.append({'varid': 10, 'vartype': 6, 'vargroup': 'motor', + 'varname': 'm1', 'min': 0, 'max': 65000, + 'mod': 1000}) + self.fakeLogToc.append({'varid': 11, 'vartype': 6, 'vargroup': 'motor', + 'varname': 'm2', 'min': 0, 'max': 65000, + 'mod': 1000}) + self.fakeLogToc.append({'varid': 12, 'vartype': 6, 'vargroup': 'motor', + 'varname': 'm3', 'min': 0, 'max': 65000, + 'mod': 1000}) + self.fakeLogToc.append({'varid': 13, 'vartype': 6, 'vargroup': 'motor', + 'varname': 'm4', 'min': 0, 'max': 65000, + 'mod': 1000}) + self.fakeLogToc.append({'varid': 14, 'vartype': 2, + 'vargroup': 'stabilizer', 'varname': 'thrust', + 'min': 0, 'max': 65000, 'mod': 1000}) + self.fakeLogToc.append({'varid': 15, 'vartype': 7, + 'vargroup': 'baro', 'varname': 'asl', + 'min': 540, 'max': 545, 'mod': 0.5}) + self.fakeLogToc.append({'varid': 16, 'vartype': 7, + 'vargroup': 'baro', 'varname': 'aslRaw', + 'min': 540, 'max': 545, 'mod': 1.0}) + self.fakeLogToc.append({'varid': 17, 'vartype': 7, + 'vargroup': 'baro', 'varname': 'aslLong', + 'min': 540, 'max': 545, 'mod': 0.5}) + self.fakeLogToc.append({'varid': 18, 'vartype': 7, + 'vargroup': 'baro', 'varname': 'temp', + 'min': 26, 'max': 38, 'mod': 1.0}) + self.fakeLogToc.append({'varid': 19, 'vartype': 7, + 'vargroup': 'altHold', 'varname': 'target', + 'min': 542, 'max': 543, 'mod': 0.1}) + self.fakeLogToc.append({'varid': 20, 'vartype': 6, + 'vargroup': 'gps', 'varname': 'lat', + 'min': 556112190, 'max': 556112790, + 'mod': 10}) + self.fakeLogToc.append({'varid': 21, 'vartype': 6, + 'vargroup': 'gps', 'varname': 'lon', + 'min': 129945110, 'max': 129945710, + 'mod': 10}) + self.fakeLogToc.append({'varid': 22, 'vartype': 6, + 'vargroup': 'gps', 'varname': 'hMSL', + 'min': 0, 'max': 100000, + 'mod': 1000}) + self.fakeLogToc.append({'varid': 23, 'vartype': 6, + 'vargroup': 'gps', 'varname': 'heading', + 'min': -10000000, 'max': 10000000, + 'mod': 100000}) + self.fakeLogToc.append({'varid': 24, 'vartype': 6, + 'vargroup': 'gps', 'varname': 'gSpeed', + 'min': 0, 'max': 1000, + 'mod': 100}) + self.fakeLogToc.append({'varid': 25, 'vartype': 3, + 'vargroup': 'gps', 'varname': 'hAcc', + 'min': 0, 'max': 5000, + 'mod': 100}) + self.fakeLogToc.append({'varid': 26, 'vartype': 1, + 'vargroup': 'gps', 'varname': 'fixType', + 'min': 0, 'max': 5, + 'mod': 1}) # Fill up the fake logging TOC with values and data self.fakeParamToc = [] - self.fakeParamToc.append({"varid": 0, "vartype": 0x08, - "vargroup": "blah", "varname": "p", - "writable": True, "value": 100}) - self.fakeParamToc.append({"varid": 1, "vartype": 0x0A, - "vargroup": "info", "varname": "cid", - "writable": False, "value": 1234}) - self.fakeParamToc.append({"varid": 2, "vartype": 0x06, - "vargroup": "rpid", "varname": "prp", - "writable": True, "value": 1.5}) - self.fakeParamToc.append({"varid": 3, "vartype": 0x06, - "vargroup": "rpid", "varname": "pyaw", - "writable": True, "value": 2.5}) - self.fakeParamToc.append({"varid": 4, "vartype": 0x06, - "vargroup": "rpid", "varname": "irp", - "writable": True, "value": 3.5}) - self.fakeParamToc.append({"varid": 5, "vartype": 0x06, - "vargroup": "rpid", "varname": "iyaw", - "writable": True, "value": 4.5}) - self.fakeParamToc.append({"varid": 6, "vartype": 0x06, - "vargroup": "pid_attitude", - "varname": "pitch_kd", "writable": True, - "value": 5.5}) - self.fakeParamToc.append({"varid": 7, "vartype": 0x06, - "vargroup": "rpid", "varname": "dyaw", - "writable": True, "value": 6.5}) - self.fakeParamToc.append({"varid": 8, "vartype": 0x06, - "vargroup": "apid", "varname": "prp", - "writable": True, "value": 7.5}) - self.fakeParamToc.append({"varid": 9, "vartype": 0x06, - "vargroup": "apid", "varname": "pyaw", - "writable": True, "value": 8.5}) - self.fakeParamToc.append({"varid": 10, "vartype": 0x06, - "vargroup": "apid", "varname": "irp", - "writable": True, "value": 9.5}) - self.fakeParamToc.append({"varid": 11, "vartype": 0x06, - "vargroup": "apid", "varname": "iyaw", - "writable": True, "value": 10.5}) - self.fakeParamToc.append({"varid": 12, "vartype": 0x06, - "vargroup": "apid", "varname": "drp", - "writable": True, "value": 11.5}) - self.fakeParamToc.append({"varid": 13, "vartype": 0x06, - "vargroup": "apid", "varname": "dyaw", - "writable": True, "value": 12.5}) - self.fakeParamToc.append({"varid": 14, "vartype": 0x08, - "vargroup": "flightctrl", - "varname": "xmode", "writable": True, - "value": 1}) - self.fakeParamToc.append({"varid": 15, "vartype": 0x08, - "vargroup": "flightctrl", - "varname": "ratepid", "writable": True, - "value": 1}) - self.fakeParamToc.append({"varid": 16, "vartype": 0x08, - "vargroup": "imu_sensors", - "varname": "HMC5883L", "writable": False, - "value": 1}) - self.fakeParamToc.append({"varid": 17, "vartype": 0x08, - "vargroup": "imu_sensors", - "varname": "MS5611", "writable": False, - "value": 1}) - self.fakeParamToc.append({"varid": 18, "vartype": 0x0A, - "vargroup": "firmware", - "varname": "revision0", "writable": False, - "value": 0xdeb}) - self.fakeParamToc.append({"varid": 19, "vartype": 0x09, - "vargroup": "firmware", - "varname": "revision1", "writable": False, - "value": 0x99}) - self.fakeParamToc.append({"varid": 20, "vartype": 0x08, - "vargroup": "firmware", - "varname": "modified", "writable": False, - "value": 1}) - self.fakeParamToc.append({"varid": 21, "vartype": 0x08, - "vargroup": "imu_tests", - "varname": "MPU6050", "writable": False, - "value": 1}) - self.fakeParamToc.append({"varid": 22, "vartype": 0x08, - "vargroup": "imu_tests", - "varname": "HMC5883L", "writable": False, - "value": 1}) - self.fakeParamToc.append({"varid": 23, "vartype": 0x08, - "vargroup": "imu_tests", - "varname": "MS5611", "writable": False, - "value": 1}) + self.fakeParamToc.append({'varid': 0, 'vartype': 0x08, + 'vargroup': 'blah', 'varname': 'p', + 'writable': True, 'value': 100}) + self.fakeParamToc.append({'varid': 1, 'vartype': 0x0A, + 'vargroup': 'info', 'varname': 'cid', + 'writable': False, 'value': 1234}) + self.fakeParamToc.append({'varid': 2, 'vartype': 0x06, + 'vargroup': 'rpid', 'varname': 'prp', + 'writable': True, 'value': 1.5}) + self.fakeParamToc.append({'varid': 3, 'vartype': 0x06, + 'vargroup': 'rpid', 'varname': 'pyaw', + 'writable': True, 'value': 2.5}) + self.fakeParamToc.append({'varid': 4, 'vartype': 0x06, + 'vargroup': 'rpid', 'varname': 'irp', + 'writable': True, 'value': 3.5}) + self.fakeParamToc.append({'varid': 5, 'vartype': 0x06, + 'vargroup': 'rpid', 'varname': 'iyaw', + 'writable': True, 'value': 4.5}) + self.fakeParamToc.append({'varid': 6, 'vartype': 0x06, + 'vargroup': 'pid_attitude', + 'varname': 'pitch_kd', 'writable': True, + 'value': 5.5}) + self.fakeParamToc.append({'varid': 7, 'vartype': 0x06, + 'vargroup': 'rpid', 'varname': 'dyaw', + 'writable': True, 'value': 6.5}) + self.fakeParamToc.append({'varid': 8, 'vartype': 0x06, + 'vargroup': 'apid', 'varname': 'prp', + 'writable': True, 'value': 7.5}) + self.fakeParamToc.append({'varid': 9, 'vartype': 0x06, + 'vargroup': 'apid', 'varname': 'pyaw', + 'writable': True, 'value': 8.5}) + self.fakeParamToc.append({'varid': 10, 'vartype': 0x06, + 'vargroup': 'apid', 'varname': 'irp', + 'writable': True, 'value': 9.5}) + self.fakeParamToc.append({'varid': 11, 'vartype': 0x06, + 'vargroup': 'apid', 'varname': 'iyaw', + 'writable': True, 'value': 10.5}) + self.fakeParamToc.append({'varid': 12, 'vartype': 0x06, + 'vargroup': 'apid', 'varname': 'drp', + 'writable': True, 'value': 11.5}) + self.fakeParamToc.append({'varid': 13, 'vartype': 0x06, + 'vargroup': 'apid', 'varname': 'dyaw', + 'writable': True, 'value': 12.5}) + self.fakeParamToc.append({'varid': 14, 'vartype': 0x08, + 'vargroup': 'flightctrl', + 'varname': 'xmode', 'writable': True, + 'value': 1}) + self.fakeParamToc.append({'varid': 15, 'vartype': 0x08, + 'vargroup': 'flightctrl', + 'varname': 'ratepid', 'writable': True, + 'value': 1}) + self.fakeParamToc.append({'varid': 16, 'vartype': 0x08, + 'vargroup': 'imu_sensors', + 'varname': 'HMC5883L', 'writable': False, + 'value': 1}) + self.fakeParamToc.append({'varid': 17, 'vartype': 0x08, + 'vargroup': 'imu_sensors', + 'varname': 'MS5611', 'writable': False, + 'value': 1}) + self.fakeParamToc.append({'varid': 18, 'vartype': 0x0A, + 'vargroup': 'firmware', + 'varname': 'revision0', 'writable': False, + 'value': 0xdeb}) + self.fakeParamToc.append({'varid': 19, 'vartype': 0x09, + 'vargroup': 'firmware', + 'varname': 'revision1', 'writable': False, + 'value': 0x99}) + self.fakeParamToc.append({'varid': 20, 'vartype': 0x08, + 'vargroup': 'firmware', + 'varname': 'modified', 'writable': False, + 'value': 1}) + self.fakeParamToc.append({'varid': 21, 'vartype': 0x08, + 'vargroup': 'imu_tests', + 'varname': 'MPU6050', 'writable': False, + 'value': 1}) + self.fakeParamToc.append({'varid': 22, 'vartype': 0x08, + 'vargroup': 'imu_tests', + 'varname': 'HMC5883L', 'writable': False, + 'value': 1}) + self.fakeParamToc.append({'varid': 23, 'vartype': 0x08, + 'vargroup': 'imu_tests', + 'varname': 'MS5611', 'writable': False, + 'value': 1}) self.fakeflash = {} self._random_answer_delay = True @@ -285,25 +283,25 @@ class DebugDriver(CRTPDriver): self._packet_handler.start() def scan_interface(self, address): - return [["debug://0/0", "Normal connection"], - ["debug://0/1", "Fail to connect"], - ["debug://0/2", "Incomplete log TOC download"], - ["debug://0/3", "Insert random delays on replies"], - ["debug://0/4", - "Insert random delays on replies and random TOC CRCs"], - ["debug://0/5", "Normal but random TOC CRCs"], - ["debug://0/6", "Normal but empty I2C and OW mems"]] + return [['debug://0/0', 'Normal connection'], + ['debug://0/1', 'Fail to connect'], + ['debug://0/2', 'Incomplete log TOC download'], + ['debug://0/3', 'Insert random delays on replies'], + ['debug://0/4', + 'Insert random delays on replies and random TOC CRCs'], + ['debug://0/5', 'Normal but random TOC CRCs'], + ['debug://0/6', 'Normal but empty I2C and OW mems']] def get_status(self): - return "Ok" + return 'Ok' def get_name(self): - return "debug" + return 'debug' def connect(self, uri, linkQualityCallback, linkErrorCallback): - if not re.search("^debug://", uri): - raise WrongUriType("Not a debug URI") + if not re.search('^debug://', uri): + raise WrongUriType('Not a debug URI') self._packet_handler.linkErrorCallback = linkErrorCallback self._packet_handler.linkQualityCallback = linkQualityCallback @@ -316,18 +314,18 @@ class DebugDriver(CRTPDriver): self._packet_handler._random_answer_delay = False self._packet_handler._random_toc_crcs = False - if (re.search("^debug://.*/1\Z", uri)): + if (re.search('^debug://.*/1\Z', uri)): self._packet_handler.inhibitAnswers = True - if (re.search("^debug://.*/110\Z", uri)): + if (re.search('^debug://.*/110\Z', uri)): self._packet_handler.bootloader = True - if (re.search("^debug://.*/2\Z", uri)): + if (re.search('^debug://.*/2\Z', uri)): self._packet_handler.doIncompleteLogTOC = True - if (re.search("^debug://.*/3\Z", uri)): + if (re.search('^debug://.*/3\Z', uri)): self._packet_handler._random_answer_delay = True - if (re.search("^debug://.*/4\Z", uri)): + if (re.search('^debug://.*/4\Z', uri)): self._packet_handler._random_answer_delay = True self._packet_handler._random_toc_crcs = True - if (re.search("^debug://.*/5\Z", uri)): + if (re.search('^debug://.*/5\Z', uri)): self._packet_handler._random_toc_crcs = True if len(self._fake_mems) == 0: @@ -359,8 +357,8 @@ class DebugDriver(CRTPDriver): FakeMemory(type=1, size=112, addr=0x1234567890ABCDEE, data=[0x00 for a in range(112)])) - if (re.search("^debug://.*/6\Z", uri)): - logger.info("------------->Erasing memories on connect") + if (re.search('^debug://.*/6\Z', uri)): + logger.info('------------->Erasing memories on connect') for m in self._fake_mems: m.erase() @@ -395,7 +393,7 @@ class DebugDriver(CRTPDriver): self._packet_handler.handle_packet(pk) def close(self): - logger.info("Closing debugdriver") + logger.info('Closing debugdriver') for f in self._packet_handler.fakeLoggingThreads: f.stop() if self.fakeConsoleThread: @@ -438,10 +436,10 @@ class _PacketHandlingThread(Thread): if (self.inhibitAnswers): self.nowAnswerCounter = self.nowAnswerCounter - 1 logger.debug( - "Not answering with any data, will send link errori" - " in %d retries", self.nowAnswerCounter) + 'Not answering with any data, will send link errori' + ' in %d retries', self.nowAnswerCounter) if (self.nowAnswerCounter == 0): - self.linkErrorCallback("Nothing is answering, and it" + self.linkErrorCallback('Nothing is answering, and it' " shouldn't") else: if (pk.port == 0xFF): @@ -458,7 +456,7 @@ class _PacketHandlingThread(Thread): self._handle_mem_access(pk) else: logger.warning( - "Not handling incoming packets on port [%d]", + 'Not handling incoming packets on port [%d]', pk.port) def _handle_mem_access(self, pk): @@ -473,7 +471,7 @@ class _PacketHandlingThread(Thread): p_out.data = (1, len(self._fake_mems)) if cmd == 2: id = payload[0] - logger.info("Getting mem {}".format(id)) + logger.info('Getting mem {}'.format(id)) m = self._fake_mems[id] p_out.data = struct.pack( '<BBBIQ', 2, id, m.type, m.size, m.addr) @@ -481,24 +479,24 @@ class _PacketHandlingThread(Thread): if chan == 1: # Read channel id = cmd - addr = struct.unpack("I", payload[0:4])[0] + addr = struct.unpack('I', payload[0:4])[0] length = payload[4] status = 0 - logger.info("MEM: Read {}bytes at 0x{:X} from memory {}".format( + logger.info('MEM: Read {}bytes at 0x{:X} from memory {}'.format( length, addr, id)) m = self._fake_mems[id] p_out = CRTPPacket() p_out.set_header(CRTPPort.MEM, 1) - p_out.data = struct.pack("<BIB", id, addr, status) - p_out.data += struct.pack("B" * length, + p_out.data = struct.pack('<BIB', id, addr, status) + p_out.data += struct.pack('B' * length, *m.data[addr:addr + length]) self._send_packet(p_out) if chan == 2: # Write channel id = cmd - addr = struct.unpack("I", payload[0:4])[0] + addr = struct.unpack('I', payload[0:4])[0] data = payload[4:] - logger.info("MEM: Write {}bytes at 0x{:X} to memory {}".format( + logger.info('MEM: Write {}bytes at 0x{:X} to memory {}'.format( len(data), addr, id)) m = self._fake_mems[id] @@ -509,7 +507,7 @@ class _PacketHandlingThread(Thread): p_out = CRTPPacket() p_out.set_header(CRTPPort.MEM, 2) - p_out.data = struct.pack("<BIB", id, addr, status) + p_out.data = struct.pack('<BIB', id, addr, status) self._send_packet(p_out) def _handle_bootloader(self, pk): @@ -525,7 +523,7 @@ class _PacketHandlingThread(Thread): flashPages, flashStart) p.data += struct.pack('B' * 12, 0xA0A1A2A3A4A5) self._send_packet(p) - logging.info("Bootloader: Sending info back info") + logging.info('Bootloader: Sending info back info') elif (cmd == 0x14): # Upload buffer [page, addr] = struct.unpack('<HH', p.data[0:4]) elif (cmd == 0x18): # Flash page @@ -534,29 +532,29 @@ class _PacketHandlingThread(Thread): p.data = struct.pack('<BBH', 0xFF, 0x18, 1) self._send_packet(p) elif (cmd == 0xFF): # Reset to firmware - logger.info("Bootloader: Got reset command") + logger.info('Bootloader: Got reset command') else: - logger.warning("Bootloader: Unknown command 0x%02X", cmd) + logger.warning('Bootloader: Unknown command 0x%02X', cmd) def _handle_debugmessage(self, pk): if (pk.channel == 0): - cmd = struct.unpack("B", pk.data[0])[0] + cmd = struct.unpack('B', pk.data[0])[0] if (cmd == 0): # Fake link quality - newLinkQuality = struct.unpack("B", pk.data[1])[0] + newLinkQuality = struct.unpack('B', pk.data[1])[0] self.linkQualityCallback(newLinkQuality) elif (cmd == 1): - self.linkErrorCallback("DebugDriver was forced to disconnect!") + self.linkErrorCallback('DebugDriver was forced to disconnect!') else: - logger.warning("Debug port: Not handling cmd=%d on channel 0", + logger.warning('Debug port: Not handling cmd=%d on channel 0', cmd) else: - logger.warning("Debug port: Not handling channel=%d", + logger.warning('Debug port: Not handling channel=%d', pk.channel) def _handle_toc_access(self, pk): chan = pk.channel cmd = pk.data[0] - logger.info("TOC access on port %d", pk.port) + logger.info('TOC access on port %d', pk.port) if (chan == 0): # TOC Access cmd = pk.data[0] if (cmd == 0): # Reqest variable info @@ -565,26 +563,26 @@ class _PacketHandlingThread(Thread): varIndex = 0 if (len(pk.data) > 1): varIndex = pk.data[1] - logger.debug("TOC[%d]: Requesting ID=%d", pk.port, + logger.debug('TOC[%d]: Requesting ID=%d', pk.port, varIndex) else: - logger.debug("TOC[%d]: Requesting first index..surprise," - " it 0 !", pk.port) + logger.debug('TOC[%d]: Requesting first index..surprise,' + ' it 0 !', pk.port) if (pk.port == CRTPPort.LOGGING): l = self.fakeLogToc[varIndex] if (pk.port == CRTPPort.PARAM): l = self.fakeParamToc[varIndex] - vartype = l["vartype"] - if (pk.port == CRTPPort.PARAM and l["writable"] is True): + vartype = l['vartype'] + if (pk.port == CRTPPort.PARAM and l['writable'] is True): vartype = vartype | (0x10) - p.data = struct.pack("<BBB", cmd, l["varid"], vartype) - for ch in l["vargroup"]: + p.data = struct.pack('<BBB', cmd, l['varid'], vartype) + for ch in l['vargroup']: p.data.append(ord(ch)) p.data.append(0) - for ch in l["varname"]: + for ch in l['varname']: p.data.append(ord(ch)) p.data.append(0) if (self.doIncompleteLogTOC is False): @@ -592,8 +590,8 @@ class _PacketHandlingThread(Thread): elif (varIndex < 5): self._send_packet(p) else: - logger.info("TOC: Doing incomplete TOC, stopping after" - " varIndex => 5") + logger.info('TOC: Doing incomplete TOC, stopping after' + ' varIndex => 5') if (cmd == 1): # TOC CRC32 request fakecrc = 0 @@ -606,11 +604,11 @@ class _PacketHandlingThread(Thread): if self._random_toc_crcs: fakecrc = int(''.join( - random.choice("ABCDEF" + string.digits) for x in + random.choice('ABCDEF' + string.digits) for x in range(8)), 16) - logger.debug("Generated random TOC CRC: 0x%x", fakecrc) - logger.info("TOC[%d]: Requesting TOC CRC, sending back fake" - " stuff: %d", pk.port, len(self.fakeLogToc)) + logger.debug('Generated random TOC CRC: 0x%x', fakecrc) + logger.info('TOC[%d]: Requesting TOC CRC, sending back fake' + ' stuff: %d', pk.port, len(self.fakeLogToc)) p = CRTPPacket() p.set_header(pk.port, 0) p.data = struct.pack('<BBIBB', 1, tocLen, fakecrc, 16, 24) @@ -619,23 +617,23 @@ class _PacketHandlingThread(Thread): def handleParam(self, pk): chan = pk.channel cmd = pk.data[0] - logger.debug("PARAM: Port=%d, Chan=%d, cmd=%d", pk.port, + logger.debug('PARAM: Port=%d, Chan=%d, cmd=%d', pk.port, chan, cmd) if (chan == 0): # TOC Access self._handle_toc_access(pk) elif (chan == 2): # Settings access varId = pk.data[0] formatStr = ParamTocElement.types[ - self.fakeParamToc[varId]["vartype"]][1] + self.fakeParamToc[varId]['vartype']][1] newvalue = struct.unpack(formatStr, pk.data[1:])[0] - self.fakeParamToc[varId]["value"] = newvalue - logger.info("PARAM: New value [%s] for param [%d]", newvalue, + self.fakeParamToc[varId]['value'] = newvalue + logger.info('PARAM: New value [%s] for param [%d]', newvalue, varId) # Send back the new value p = CRTPPacket() p.set_header(pk.port, 2) - p.data += struct.pack("<B", varId) - p.data += struct.pack(formatStr, self.fakeParamToc[varId]["value"]) + p.data += struct.pack('<B', varId) + p.data += struct.pack(formatStr, self.fakeParamToc[varId]['value']) self._send_packet(p) elif (chan == 1): p = CRTPPacket() @@ -643,15 +641,15 @@ class _PacketHandlingThread(Thread): varId = cmd p.data.append(varId) formatStr = ParamTocElement.types[ - self.fakeParamToc[varId]["vartype"]][1] - p.data += struct.pack(formatStr, self.fakeParamToc[varId]["value"]) - logger.info("PARAM: Getting value for %d", varId) + self.fakeParamToc[varId]['vartype']][1] + p.data += struct.pack(formatStr, self.fakeParamToc[varId]['value']) + logger.info('PARAM: Getting value for %d', varId) self._send_packet(p) def _handle_logging(self, pk): chan = pk.channel cmd = pk.data[0] - logger.debug("LOG: Chan=%d, cmd=%d", chan, cmd) + logger.debug('LOG: Chan=%d, cmd=%d', chan, cmd) if (chan == 0): # TOC Access self._handle_toc_access(pk) elif (chan == 1): # Settings access @@ -659,7 +657,7 @@ class _PacketHandlingThread(Thread): blockId = pk.data[1] if blockId not in self._added_blocks: self._added_blocks.append(blockId) - logger.info("LOG:Adding block id=%d", blockId) + logger.info('LOG:Adding block id=%d', blockId) listofvars = pk.data[3:] fakeThread = _FakeLoggingDataThread(self.queue, blockId, listofvars, @@ -677,10 +675,10 @@ class _PacketHandlingThread(Thread): p.data = struct.pack('<BBB', 0, blockId, errno.EEXIST) self._send_packet(p) if (cmd == 1): - logger.warning("LOG: Appending block not implemented!") + logger.warning('LOG: Appending block not implemented!') if (cmd == 2): blockId = pk.data[1] - logger.info("LOG: Should delete block %d", blockId) + logger.info('LOG: Should delete block %d', blockId) success = False for fb in self.fakeLoggingThreads: if (fb.blockId == blockId): @@ -691,17 +689,17 @@ class _PacketHandlingThread(Thread): p.set_header(5, 1) p.data = struct.pack('<BBB', cmd, blockId, 0x00) self._send_packet(p) - logger.info("LOG: Deleted block=%d", blockId) + logger.info('LOG: Deleted block=%d', blockId) success = True if (success is False): - logger.warning("LOG: Could not delete block=%d, not found", + logger.warning('LOG: Could not delete block=%d, not found', blockId) # TODO: Send back error code if (cmd == 3): blockId = pk.data[1] period = pk.data[2] * 10 # Sent as multiple of 10 ms - logger.info("LOG:Starting block %d", blockId) + logger.info('LOG:Starting block %d', blockId) success = False for fb in self.fakeLoggingThreads: if (fb.blockId == blockId): @@ -711,15 +709,15 @@ class _PacketHandlingThread(Thread): p.set_header(5, 1) p.data = struct.pack('<BBB', cmd, blockId, 0x00) self._send_packet(p) - logger.info("LOG:Started block=%d", blockId) + logger.info('LOG:Started block=%d', blockId) success = True if (success is False): - logger.info("LOG:Could not start block=%d, not found", + logger.info('LOG:Could not start block=%d, not found', blockId) # TODO: Send back error code if (cmd == 4): blockId = pk.data[1] - logger.info("LOG:Pausing block %d", blockId) + logger.info('LOG:Pausing block %d', blockId) success = False for fb in self.fakeLoggingThreads: if (fb.blockId == blockId): @@ -728,22 +726,22 @@ class _PacketHandlingThread(Thread): p.set_header(5, 1) p.data = struct.pack('<BBB', cmd, blockId, 0x00) self._send_packet(p) - logger.info("LOG:Pause block=%d", blockId) + logger.info('LOG:Pause block=%d', blockId) success = True if (success is False): - logger.warning("LOG:Could not pause block=%d, not found", + logger.warning('LOG:Could not pause block=%d, not found', blockId) # TODO: Send back error code if (cmd == 5): - logger.info("LOG: Reset logging, but doing nothing") + logger.info('LOG: Reset logging, but doing nothing') p = CRTPPacket() p.set_header(5, 1) p.data = struct.pack('<BBB', cmd, 0x00, 0x00) self._send_packet(p) elif (chan > 1): - logger.warning("LOG: Uplink packets with channels > 1 not" - " supported!") + logger.warning('LOG: Uplink packets with channels > 1 not' + ' supported!') def _send_packet(self, pk): # Do not delay log data @@ -751,7 +749,7 @@ class _PacketHandlingThread(Thread): pk.channel != 0x02): # Calculate a delay between 0ms and 250ms delay = random.randint(0, 250) / 1000.0 - logger.debug("Delaying answer %.2fms", delay * 1000) + logger.debug('Delaying answer %.2fms', delay * 1000) time.sleep(delay) self.queue.put(pk) @@ -771,41 +769,41 @@ class _FakeLoggingDataThread(Thread): self.shouldLog = False self.fakeLogToc = fakeLogToc self.fakeLoggingData = [] - self.setName("Fakelog block=%d" % blockId) + self.setName('Fakelog block=%d' % blockId) self.shouldQuit = False - logging.info("FakeDataLoggingThread created for blockid=%d", blockId) + logging.info('FakeDataLoggingThread created for blockid=%d', blockId) i = 0 while (i < len(listofvars)): varType = listofvars[i] var_stored_as = (varType >> 8) var_fetch_as = (varType & 0xFF) if (var_stored_as > 0): - addr = struct.unpack("<I", listofvars[i + 1:i + 5]) - logger.debug("FakeLoggingThread: We should log a memory addr" - " 0x%04X", addr) + addr = struct.unpack('<I', listofvars[i + 1:i + 5]) + logger.debug('FakeLoggingThread: We should log a memory addr' + ' 0x%04X', addr) self.fakeLoggingData.append([memlogging[var_fetch_as], - memlogging[var_fetch_as]["min"], + memlogging[var_fetch_as]['min'], 1]) i = i + 5 else: varId = listofvars[i] - logger.debug("FakeLoggingThread: We should log variable from" - " TOC: id=%d, type=0x%02X", varId, varType) + logger.debug('FakeLoggingThread: We should log variable from' + ' TOC: id=%d, type=0x%02X', varId, varType) for t in self.fakeLogToc: - if (varId == t["varid"]): + if (varId == t['varid']): # Each touple will have var data and current fake value - self.fakeLoggingData.append([t, t["min"], 1]) + self.fakeLoggingData.append([t, t['min'], 1]) i = i + 2 def _enable_logging(self): self.shouldLog = True - logging.info("_FakeLoggingDataThread: Enable thread [%s] at period %d", + logging.info('_FakeLoggingDataThread: Enable thread [%s] at period %d', self.getName(), self.period) def _disable_logging(self): self.shouldLog = False - logging.info("_FakeLoggingDataThread: Disable thread [%s]", + logging.info('_FakeLoggingDataThread: Disable thread [%s]', self.getName()) def stop(self): @@ -826,16 +824,16 @@ class _FakeLoggingDataThread(Thread): for d in self.fakeLoggingData: # Set new value - d[1] = d[1] + d[0]["mod"] * d[2] + d[1] = d[1] + d[0]['mod'] * d[2] # Obej the limitations - if (d[1] > d[0]["max"]): - d[1] = d[0]["max"] # Limit value + if (d[1] > d[0]['max']): + d[1] = d[0]['max'] # Limit value d[2] = -1 # Switch direction - if (d[1] < d[0]["min"]): - d[1] = d[0]["min"] # Limit value + if (d[1] < d[0]['min']): + d[1] = d[0]['min'] # Limit value d[2] = 1 # Switch direction # Pack value - formatStr = LogTocElement.types[d[0]["vartype"]][1] + formatStr = LogTocElement.types[d[0]['vartype']][1] p.data += struct.pack(formatStr, d[1]) self.outQueue.put(p) time.sleep(self.period / 1000.0) # Period in ms here @@ -865,25 +863,25 @@ class FakeConsoleThread(Thread): lat_val += 1 alt_val += 1.0 - long_string = "5536.677%d" % (long_val % 99) - lat_string = "01259.645%d" % (lat_val % 99) - alt_string = "%.1f" % (alt_val % 100.0) + long_string = '5536.677%d' % (long_val % 99) + lat_string = '01259.645%d' % (lat_val % 99) + alt_string = '%.1f' % (alt_val % 100.0) # Copy of what is sent from the module, but note that only # the GPGGA message is being simulated, the others are fixed... - self._send_text("Time is now %s\n" % datetime.now()) - self._send_text("$GPVTG,,T,,M,0.386,N,0.716,K,A*2E\n") - self._send_text("$GPGGA,135544.0") - self._send_text("0,%s,N,%s,E,1,04,2.62,3.6,M,%s,M,,*58\n" % ( + self._send_text('Time is now %s\n' % datetime.now()) + self._send_text('$GPVTG,,T,,M,0.386,N,0.716,K,A*2E\n') + self._send_text('$GPGGA,135544.0') + self._send_text('0,%s,N,%s,E,1,04,2.62,3.6,M,%s,M,,*58\n' % ( long_string, lat_string, alt_string)) self._send_text( - "$GPGSA,A,3,31,20,23,07,,,,,,,,,3.02,2.62,1.52*05\n") - self._send_text("$GPGSV,2,1,07,07,09,181,15,13,63,219,26,16,02," - "097,,17,05,233,20*7E\n") + '$GPGSA,A,3,31,20,23,07,,,,,,,,,3.02,2.62,1.52*05\n') + self._send_text('$GPGSV,2,1,07,07,09,181,15,13,63,219,26,16,02,' + '097,,17,05,233,20*7E\n') self._send_text( - "$GPGSV,2,2,07,20,42,119,35,23,77,097,27,31,12,032,19*47\n") + '$GPGSV,2,2,07,20,42,119,35,23,77,097,27,31,12,032,19*47\n') self._send_text( - "$GPGLL,5536.67734,N,01259.64578,E,135544.00,A,A*68\n") + '$GPGLL,5536.67734,N,01259.64578,E,135544.00,A,A*68\n') time.sleep(2) @@ -891,7 +889,6 @@ class FakeConsoleThread(Thread): p = CRTPPacket() p.set_header(0, 0) - us = "%is" % len(message) # This might be done prettier ;-) p.data = message diff --git a/cflib/crtp/exceptions.py b/cflib/crtp/exceptions.py index 876f9ee000e4e96560291cd0956899c7611ef9f5..9ccb6af62a9a7764b140bcb5b4843d1109337ff4 100644 --- a/cflib/crtp/exceptions.py +++ b/cflib/crtp/exceptions.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Exception used when the URI is not for the current driver (ie. radio:// for the serial driver ...) diff --git a/cflib/crtp/radiodriver.py b/cflib/crtp/radiodriver.py index 01a7b8fa72e2618179602f2880002e06a6137970..d2b85d59d3a90b53a9112f2245b35c3ac2ab3d7c 100644 --- a/cflib/crtp/radiodriver.py +++ b/cflib/crtp/radiodriver.py @@ -20,34 +20,32 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Crazyradio CRTP link driver. This driver is used to communicate with the Crazyflie using the Crazyradio USB dongle. """ - +import array +import binascii import collections import logging -import sys -from cflib.crtp.crtpdriver import CRTPDriver -from .crtpstack import CRTPPacket -from .exceptions import WrongUriType -import threading import re -import array -import binascii import struct +import sys +import threading -from cflib.drivers.crazyradio import Crazyradio from usb import USBError +from .crtpstack import CRTPPacket +from .exceptions import WrongUriType +from cflib.crtp.crtpdriver import CRTPDriver +from cflib.drivers.crazyradio import Crazyradio + if sys.version_info < (3,): import Queue as queue else: @@ -67,7 +65,7 @@ class RadioDriver(CRTPDriver): """ Create the link driver """ CRTPDriver.__init__(self) self.cradio = None - self.uri = "" + self.uri = '' self.link_error_callback = None self.link_quality_callback = None self.in_queue = None @@ -87,16 +85,16 @@ class RadioDriver(CRTPDriver): """ # check if the URI is a radio URI - if not re.search("^radio://", uri): - raise WrongUriType("Not a radio URI") + if not re.search('^radio://', uri): + raise WrongUriType('Not a radio URI') # Open the USB dongle - if not re.search("^radio://([0-9]+)((/([0-9]+))" - "((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$", uri): + if not re.search('^radio://([0-9]+)((/([0-9]+))' + '((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$', uri): raise WrongUriType('Wrong radio URI format!') - uri_data = re.search("^radio://([0-9]+)((/([0-9]+))" - "((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$", uri) + uri_data = re.search('^radio://([0-9]+)((/([0-9]+))' + '((/(250K|1M|2M))?(/([A-F0-9]+))?)?)?$', uri) self.uri = uri @@ -105,22 +103,22 @@ class RadioDriver(CRTPDriver): channel = int(uri_data.group(4)) datarate = Crazyradio.DR_2MPS - if uri_data.group(7) == "250K": + if uri_data.group(7) == '250K': datarate = Crazyradio.DR_250KPS - if uri_data.group(7) == "1M": + if uri_data.group(7) == '1M': datarate = Crazyradio.DR_1MPS - if uri_data.group(7) == "2M": + if uri_data.group(7) == '2M': datarate = Crazyradio.DR_2MPS if self.cradio is None: self.cradio = Crazyradio(devid=int(uri_data.group(1))) else: - raise Exception("Link already open!") + raise Exception('Link already open!') if self.cradio.version >= 0.4: self.cradio.set_arc(10) else: - logger.warning("Radio version <0.4 will be obsoleted soon!") + logger.warning('Radio version <0.4 will be obsoleted soon!') self.cradio.set_channel(channel) @@ -128,7 +126,7 @@ class RadioDriver(CRTPDriver): if uri_data.group(9): addr = str(uri_data.group(9)) - new_addr = struct.unpack("<BBBBB", binascii.unhexlify(addr)) + new_addr = struct.unpack('<BBBBB', binascii.unhexlify(addr)) self.cradio.set_address(new_addr) # Prepare the inter-thread communication queue @@ -178,8 +176,8 @@ class RadioDriver(CRTPDriver): self.out_queue.put(pk, True, 2) except queue.Full: if self.link_error_callback: - self.link_error_callback("RadioDriver: Could not send packet" - " to copter") + self.link_error_callback('RadioDriver: Could not send packet' + ' to copter') def pause(self): self._thread.stop() @@ -225,21 +223,21 @@ class RadioDriver(CRTPDriver): to_scan = () for l in links: one_to_scan = {} - uri_data = re.search("^radio://([0-9]+)((/([0-9]+))" - "(/(250K|1M|2M))?)?$", + uri_data = re.search('^radio://([0-9]+)((/([0-9]+))' + '(/(250K|1M|2M))?)?$', l) - one_to_scan["channel"] = int(uri_data.group(4)) + one_to_scan['channel'] = int(uri_data.group(4)) datarate = Crazyradio.DR_2MPS - if uri_data.group(6) == "250K": + if uri_data.group(6) == '250K': datarate = Crazyradio.DR_250KPS - if uri_data.group(6) == "1M": + if uri_data.group(6) == '1M': datarate = Crazyradio.DR_1MPS - if uri_data.group(6) == "2M": + if uri_data.group(6) == '2M': datarate = Crazyradio.DR_2MPS - one_to_scan["datarate"] = datarate + one_to_scan['datarate'] = datarate to_scan += (one_to_scan,) @@ -247,15 +245,15 @@ class RadioDriver(CRTPDriver): ret = () for f in found: - dr_string = "" - if f["datarate"] == Crazyradio.DR_2MPS: - dr_string = "2M" - if f["datarate"] == Crazyradio.DR_250KPS: - dr_string = "250K" - if f["datarate"] == Crazyradio.DR_1MPS: - dr_string = "1M" + dr_string = '' + if f['datarate'] == Crazyradio.DR_2MPS: + dr_string = '2M' + if f['datarate'] == Crazyradio.DR_250KPS: + dr_string = '250K' + if f['datarate'] == Crazyradio.DR_1MPS: + dr_string = '1M' - ret += ("radio://0/{}/{}".format(f["channel"], dr_string),) + ret += ('radio://0/{}/{}'.format(f['channel'], dr_string),) return ret @@ -267,18 +265,18 @@ class RadioDriver(CRTPDriver): except Exception: return [] else: - raise Exception("Cannot scann for links while the link is open!") + raise Exception('Cannot scann for links while the link is open!') # FIXME: implements serial number in the Crazyradio driver! - serial = "N/A" + serial = 'N/A' - logger.info("v%s dongle with serial %s found", self.cradio.version, + logger.info('v%s dongle with serial %s found', self.cradio.version, serial) found = [] if address is not None: - addr = "{:X}".format(address) - new_addr = struct.unpack("<BBBBB", binascii.unhexlify(addr)) + addr = '{:X}'.format(address) + new_addr = struct.unpack('<BBBBB', binascii.unhexlify(addr)) self.cradio.set_address(new_addr) self.cradio.set_arc(1) @@ -286,22 +284,22 @@ class RadioDriver(CRTPDriver): self.cradio.set_data_rate(self.cradio.DR_250KPS) if address is None or address == 0xE7E7E7E7E7: - found += [["radio://0/{}/250K".format(c), ""] + found += [['radio://0/{}/250K'.format(c), ''] for c in self._scan_radio_channels()] self.cradio.set_data_rate(self.cradio.DR_1MPS) - found += [["radio://0/{}/1M".format(c), ""] + found += [['radio://0/{}/1M'.format(c), ''] for c in self._scan_radio_channels()] self.cradio.set_data_rate(self.cradio.DR_2MPS) - found += [["radio://0/{}/2M".format(c), ""] + found += [['radio://0/{}/2M'.format(c), ''] for c in self._scan_radio_channels()] else: - found += [["radio://0/{}/250K/{:X}".format(c, address), ""] + found += [['radio://0/{}/250K/{:X}'.format(c, address), ''] for c in self._scan_radio_channels()] self.cradio.set_data_rate(self.cradio.DR_1MPS) - found += [["radio://0/{}/1M/{:X}".format(c, address), ""] + found += [['radio://0/{}/1M/{:X}'.format(c, address), ''] for c in self._scan_radio_channels()] self.cradio.set_data_rate(self.cradio.DR_2MPS) - found += [["radio://0/{}/2M/{:X}".format(c, address), ""] + found += [['radio://0/{}/2M/{:X}'.format(c, address), ''] for c in self._scan_radio_channels()] self.cradio.close() @@ -314,8 +312,8 @@ class RadioDriver(CRTPDriver): try: self.cradio = Crazyradio() except USBError as e: - return "Cannot open Crazyradio. Permission problem?" \ - " ({})".format(str(e)) + return 'Cannot open Crazyradio. Permission problem?' \ + ' ({})'.format(str(e)) except Exception as e: return str(e) @@ -323,10 +321,10 @@ class RadioDriver(CRTPDriver): self.cradio.close() self.cradio = None - return "Crazyradio version {}".format(ver) + return 'Crazyradio version {}'.format(ver) def get_name(self): - return "radio" + return 'radio' # Transmit/receive radio thread @@ -398,7 +396,7 @@ class _RadioDriverThread(threading.Thread): self.curr_up = 0 self.curr_down = 0 break - logging.info("Has safelink: {}".format(self.has_safelink)) + logging.info('Has safelink: {}'.format(self.has_safelink)) self._link.needs_resending = not self.has_safelink while (True): @@ -414,15 +412,15 @@ class _RadioDriverThread(threading.Thread): import traceback self.link_error_callback( - "Error communicating with crazy radio ,it has probably " - "been unplugged!\nException:%s\n\n%s" % ( + 'Error communicating with crazy radio ,it has probably ' + 'been unplugged!\nException:%s\n\n%s' % ( e, traceback.format_exc())) # Analise the in data packet ... if ackStatus is None: if (self.link_error_callback is not None): - self.link_error_callback("Dongle communication error" - " (ackStatus==None)") + self.link_error_callback('Dongle communication error' + ' (ackStatus==None)') continue if (self.link_quality_callback is not None): @@ -440,7 +438,7 @@ class _RadioDriverThread(threading.Thread): self.retryBeforeDisconnect = self.retryBeforeDisconnect - 1 if (self.retryBeforeDisconnect == 0 and self.link_error_callback is not None): - self.link_error_callback("Too many packets lost") + self.link_error_callback('Too many packets lost') continue self.retryBeforeDisconnect = self.RETRYCOUNT_BEFORE_DISCONNECT diff --git a/cflib/crtp/serialdriver.py b/cflib/crtp/serialdriver.py index b307f3a047a8d62fd8b8787803c0b0b61700f270..34c54036f244d6db9347b5385b40fe5ca2fcece7 100644 --- a/cflib/crtp/serialdriver.py +++ b/cflib/crtp/serialdriver.py @@ -20,43 +20,40 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ An early serial link driver. This could still be used (after some fixing) to run high-speed CRTP with the Crazyflie. The UART can be run at 2Mbit. """ +import re from .crtpdriver import CRTPDriver - from .exceptions import WrongUriType -import re - __author__ = 'Bitcraze AB' __all__ = ['SerialDriver'] class SerialDriver(CRTPDriver): + def __init__(self): None def connect(self, uri, linkQualityCallback, linkErrorCallback): # check if the URI is a serial URI - if not re.search("^serial://", uri): - raise WrongUriType("Not a serial URI") + if not re.search('^serial://', uri): + raise WrongUriType('Not a serial URI') # Check if it is a valid serial URI - uriRe = re.search("^serial://([a-z A-Z 0-9]+)/?([0-9]+)?$", uri) + uriRe = re.search('^serial://([a-z A-Z 0-9]+)/?([0-9]+)?$', uri) if not uriRe: - raise Exception("Invalid serial URI") + raise Exception('Invalid serial URI') def get_name(self): - return "serial" + return 'serial' def scan_interface(self, address): return [] diff --git a/cflib/crtp/udpdriver.py b/cflib/crtp/udpdriver.py index d93d401d2c30855ebaa63c1b025e5b19c288a205..dfba56d5788bc54175142bd5226e1b64f673dd3e 100644 --- a/cflib/crtp/udpdriver.py +++ b/cflib/crtp/udpdriver.py @@ -20,22 +20,20 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ CRTP UDP Driver. Work either with the UDP server or with an UDP device See udpserver.py for the protocol""" +import re +import struct +import sys +from socket import socket from .crtpdriver import CRTPDriver from .crtpstack import CRTPPacket from .exceptions import WrongUriType -import sys -import re -import struct -from socket import socket if sys.version_info < (3,): import Queue as queue else: @@ -46,21 +44,22 @@ __all__ = ['UdpDriver'] class UdpDriver(CRTPDriver): + def __init__(self): None def connect(self, uri, linkQualityCallback, linkErrorCallback): # check if the URI is a radio URI - if not re.search("^udp://", uri): - raise WrongUriType("Not an UDP URI") + if not re.search('^udp://', uri): + raise WrongUriType('Not an UDP URI') self.queue = queue.Queue() self.socket = socket(socket.AF_INET, socket.SOCK_DGRAM) - self.addr = ("localhost", 7777) + self.addr = ('localhost', 7777) self.socket.connect(self.addr) # Add this to the server clients list - self.socket.sendto("\xFF\x01\x01\x01", self.addr) + self.socket.sendto('\xFF\x01\x01\x01', self.addr) def receive_packet(self, time=0): data, addr = self.socket.recvfrom(1024) @@ -84,7 +83,7 @@ class UdpDriver(CRTPDriver): return None def send_packet(self, pk): - raw = (pk.port,) + struct.unpack("B" * len(pk.data), pk.data) + raw = (pk.port,) + struct.unpack('B' * len(pk.data), pk.data) cksum = 0 for i in raw: @@ -99,10 +98,10 @@ class UdpDriver(CRTPDriver): def close(self): # Remove this from the server clients list - self.socket.sendto("\xFF\x01\x02\x02", self.addr) + self.socket.sendto('\xFF\x01\x02\x02', self.addr) def get_name(self): - return "udp" + return 'udp' def scan_interface(self, address): return [] diff --git a/cflib/crtp/usbdriver.py b/cflib/crtp/usbdriver.py index 083d9fad8e5f97c42c6ab1971f353cbdd4b0292c..475a70ba62cb92f53e0dbc48741be3daa52a5d47 100644 --- a/cflib/crtp/usbdriver.py +++ b/cflib/crtp/usbdriver.py @@ -20,30 +20,24 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Crazyflie USB driver. This driver is used to communicate with the Crazyflie using the USB connection. """ - import logging +import re +import sys +import threading -from cflib.crtp.crtpdriver import CRTPDriver from .crtpstack import CRTPPacket from .exceptions import WrongUriType -import threading -import sys -import re -import time - +from cflib.crtp.crtpdriver import CRTPDriver from cflib.drivers.cfusb import CfUsb -from usb import USBError if sys.version_info < (3,): import Queue as queue else: @@ -62,7 +56,7 @@ class UsbDriver(CRTPDriver): """ Create the link driver """ CRTPDriver.__init__(self) self.cfusb = None - self.uri = "" + self.uri = '' self.link_error_callback = None self.link_quality_callback = None self.in_queue = None @@ -82,15 +76,15 @@ class UsbDriver(CRTPDriver): """ # check if the URI is a radio URI - if not re.search("^usb://", uri): - raise WrongUriType("Not a radio URI") + if not re.search('^usb://', uri): + raise WrongUriType('Not a radio URI') # Open the USB dongle - if not re.search("^usb://([0-9]+)$", + if not re.search('^usb://([0-9]+)$', uri): raise WrongUriType('Wrong radio URI format!') - uri_data = re.search("^usb://([0-9]+)$", + uri_data = re.search('^usb://([0-9]+)$', uri) self.uri = uri @@ -101,10 +95,10 @@ class UsbDriver(CRTPDriver): self.cfusb.set_crtp_to_usb(True) else: self.cfusb = None - raise Exception("Could not open {}".format(self.uri)) + raise Exception('Could not open {}'.format(self.uri)) else: - raise Exception("Link already open!") + raise Exception('Link already open!') # Prepare the inter-thread communication queue self.in_queue = queue.Queue() @@ -154,7 +148,7 @@ class UsbDriver(CRTPDriver): except queue.Full: if self.link_error_callback: self.link_error_callback( - "UsbDriver: Could not send packet to Crazyflie") + 'UsbDriver: Could not send packet to Crazyflie') def pause(self): self._thread.stop() @@ -181,7 +175,7 @@ class UsbDriver(CRTPDriver): self.cfusb.close() except Exception as e: # If we pull out the dongle we will not make this call - logger.info("Could not close {}".format(e)) + logger.info('Could not close {}'.format(e)) pass self.cfusb = None @@ -192,11 +186,11 @@ class UsbDriver(CRTPDriver): self.cfusb = CfUsb() except Exception as e: logger.warn( - "Exception while scanning for Crazyflie USB: {}".format( + 'Exception while scanning for Crazyflie USB: {}'.format( str(e))) return [] else: - raise Exception("Cannot scan for links while the link is open!") + raise Exception('Cannot scan for links while the link is open!') # FIXME: implements serial number in the Crazyradio driver! # serial = "N/A" @@ -209,10 +203,10 @@ class UsbDriver(CRTPDriver): return found def get_status(self): - return "No information available" + return 'No information available' def get_name(self): - return "UsbCdc" + return 'UsbCdc' # Transmit/receive radio thread @@ -257,7 +251,7 @@ class _UsbReceiveThread(threading.Thread): import traceback self.link_error_callback( - "Error communicating with the Crazyflie" - " ,it has probably been unplugged!\n" - "Exception:%s\n\n%s" % (e, + 'Error communicating with the Crazyflie' + ' ,it has probably been unplugged!\n' + 'Exception:%s\n\n%s' % (e, traceback.format_exc())) diff --git a/cflib/drivers/__init__.py b/cflib/drivers/__init__.py index f074d797a973bcba4f86ae9ed1bcd86112840a72..f0fd2d73c9898d85c4451dcc81d4a7d7303e777a 100644 --- a/cflib/drivers/__init__.py +++ b/cflib/drivers/__init__.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Drivers for the link interfaces that can be used by CRTP. """ diff --git a/cflib/drivers/cfusb.py b/cflib/drivers/cfusb.py index 8e620abf1900ae56e809db4ce89c728831fdb6e5..b86d2d84c82d779da85079592b2b268879c2f914 100644 --- a/cflib/drivers/cfusb.py +++ b/cflib/drivers/cfusb.py @@ -20,23 +20,17 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ USB driver for the Crazyflie. """ - +import logging import os + import usb -import logging -import sys -import time -import array -import binascii __author__ = 'Bitcraze AB' __all__ = ['CfUsb'] @@ -50,7 +44,7 @@ try: import usb.core pyusb_backend = None - if os.name == "nt": + if os.name == 'nt': import usb.backend.libusb0 as libusb0 pyusb_backend = libusb0.get_backend() @@ -65,7 +59,7 @@ def _find_devices(): """ ret = [] - logger.info("Looking for devices....") + logger.info('Looking for devices....') if pyusb1: for d in usb.core.find(idVendor=USB_VID, idProduct=USB_PID, find_all=1, @@ -104,7 +98,7 @@ class CfUsb: self.dev.set_configuration(1) self.handle = self.dev self.version = float( - "{0:x}.{1:x}".format(self.dev.bcdDevice >> 8, + '{0:x}.{1:x}'.format(self.dev.bcdDevice >> 8, self.dev.bcdDevice & 0x0FF)) else: self.handle = self.dev.open() @@ -130,7 +124,7 @@ class CfUsb: def scan(self): # TODO: Currently only supports one device if self.dev: - return [("usb://0", "")] + return [('usb://0', '')] return [] def set_crtp_to_usb(self, crtp_to_usb): @@ -146,10 +140,10 @@ class CfUsb: and a data payload if the ack packet contained any """ try: if (pyusb1 is False): - count = self.handle.bulkWrite(1, dataOut, 20) + self.handle.bulkWrite(1, dataOut, 20) else: - count = self.handle.write(endpoint=1, data=dataOut, timeout=20) - except usb.USBError as e: + self.handle.write(endpoint=1, data=dataOut, timeout=20) + except usb.USBError: pass def receive_packet(self): @@ -165,7 +159,7 @@ class CfUsb: # Normal, the read was empty pass else: - raise IOError("Crazyflie disconnected") + raise IOError('Crazyflie disconnected') except AttributeError as e: # pyusb < 1.0 doesn't implement getting the underlying error # number and it seems as if it's not possible to detect diff --git a/cflib/drivers/crazyradio.py b/cflib/drivers/crazyradio.py index 9641fa23a0014bcc1c3b143e604a137684225402..30b827cc634d97b117a5cd17154a8e81adce4649 100644 --- a/cflib/drivers/crazyradio.py +++ b/cflib/drivers/crazyradio.py @@ -20,19 +20,17 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ USB driver for the Crazyradio USB dongle. """ - +import logging import os + import usb -import logging __author__ = 'Bitcraze AB' __all__ = ['Crazyradio'] @@ -60,7 +58,7 @@ try: import usb.core pyusb_backend = None - if os.name == "nt": + if os.name == 'nt': import usb.backend.libusb0 as libusb0 pyusb_backend = libusb0.get_backend() @@ -115,14 +113,14 @@ class Crazyradio: try: device = _find_devices()[devid] except Exception: - raise Exception("Cannot find a Crazyradio Dongle") + raise Exception('Cannot find a Crazyradio Dongle') self.dev = device if (pyusb1 is True): self.dev.set_configuration(1) self.handle = self.dev - self.version = float("{0:x}.{1:x}".format( + self.version = float('{0:x}.{1:x}'.format( self.dev.bcdDevice >> 8, self.dev.bcdDevice & 0x0FF)) else: self.handle = self.dev.open() @@ -131,10 +129,10 @@ class Crazyradio: self.version = float(self.dev.deviceVersion) if self.version < 0.3: - raise "This driver requires Crazyradio firmware V0.3+" + raise 'This driver requires Crazyradio firmware V0.3+' if self.version < 0.4: - logger.warning("You should update to Crazyradio firmware V0.4+") + logger.warning('You should update to Crazyradio firmware V0.4+') # Reset the dongle to power up settings self.set_data_rate(self.DR_2MPS) @@ -167,8 +165,8 @@ class Crazyradio: def set_address(self, address): """ Set the radio address to be used""" if len(address) != 5: - raise Exception("Crazyradio: the radio address shall be 5" - " bytes long") + raise Exception('Crazyradio: the radio address shall be 5' + ' bytes long') _send_vendor_setup(self.handle, SET_RADIO_ADDRESS, 0, 0, address) @@ -219,8 +217,8 @@ class Crazyradio: def scan_selected(self, selected, packet): result = () for s in selected: - self.set_channel(s["channel"]) - self.set_data_rate(s["datarate"]) + self.set_channel(s['channel']) + self.set_data_rate(s['datarate']) status = self.send_packet(packet) if status and status.ack: result = result + (s,) diff --git a/cflib/utils/__init__.py b/cflib/utils/__init__.py index dd277b671ca49039c8196b9338e923d4dcd3b06e..fd35e362441f40692a4ad2d5a0778bd09b9768cd 100644 --- a/cflib/utils/__init__.py +++ b/cflib/utils/__init__.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Various utilities that is needed by the cflib. """ diff --git a/cflib/utils/callbacks.py b/cflib/utils/callbacks.py index 7a90f058a3e9d7fd1a88208642a455c5eeb860c5..3102bc630f0d0a5403e5a92134eb193b36391391 100644 --- a/cflib/utils/callbacks.py +++ b/cflib/utils/callbacks.py @@ -20,12 +20,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Callback objects used in the Crazyflie library """ diff --git a/examples/basiclog.py b/examples/basiclog.py index 7c3ef8a38c54b1314e56d85c3a25cfb834ab3698..26c59c5b8a7f6e28a04069f8c55a73e88b41ea26 100644 --- a/examples/basiclog.py +++ b/examples/basiclog.py @@ -19,24 +19,21 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Simple example that connects to the first Crazyflie found, logs the Stabilizer and prints it to the console. After 10s the application disconnects and exits. """ - import logging import time from threading import Timer import cflib.crtp # noqa -from cflib.crazyflie.log import LogConfig from cflib.crazyflie import Crazyflie +from cflib.crazyflie.log import LogConfig # Only output errors from the logging framework logging.basicConfig(level=logging.ERROR) @@ -60,7 +57,7 @@ class LoggingExample: self._cf.connection_failed.add_callback(self._connection_failed) self._cf.connection_lost.add_callback(self._connection_lost) - print("Connecting to %s" % link_uri) + print('Connecting to %s' % link_uri) # Try to connect to the Crazyflie self._cf.open_link(link_uri) @@ -71,13 +68,13 @@ class LoggingExample: def _connected(self, link_uri): """ This callback is called form the Crazyflie API when a Crazyflie has been connected and the TOCs have been downloaded.""" - print("Connected to %s" % link_uri) + print('Connected to %s' % link_uri) # The definition of the logconfig can be made before connecting - self._lg_stab = LogConfig(name="Stabilizer", period_in_ms=10) - self._lg_stab.add_variable("stabilizer.roll", "float") - self._lg_stab.add_variable("stabilizer.pitch", "float") - self._lg_stab.add_variable("stabilizer.yaw", "float") + self._lg_stab = LogConfig(name='Stabilizer', period_in_ms=10) + self._lg_stab.add_variable('stabilizer.roll', 'float') + self._lg_stab.add_variable('stabilizer.pitch', 'float') + self._lg_stab.add_variable('stabilizer.yaw', 'float') # Adding the configuration cannot be done until a Crazyflie is # connected, since we need to check that the variables we @@ -91,10 +88,10 @@ class LoggingExample: # Start the logging self._lg_stab.start() except KeyError as e: - print("Could not start log configuration," - "{} not found in TOC".format(str(e))) + print('Could not start log configuration,' + '{} not found in TOC'.format(str(e))) except AttributeError: - print("Could not add Stabilizer log config, bad configuration.") + print('Could not add Stabilizer log config, bad configuration.') # Start a timer to disconnect in 10s t = Timer(5, self._cf.close_link) @@ -102,26 +99,26 @@ class LoggingExample: def _stab_log_error(self, logconf, msg): """Callback from the log API when an error occurs""" - print("Error when logging %s: %s" % (logconf.name, msg)) + print('Error when logging %s: %s' % (logconf.name, msg)) def _stab_log_data(self, timestamp, data, logconf): """Callback froma the log API when data arrives""" - print("[%d][%s]: %s" % (timestamp, logconf.name, data)) + print('[%d][%s]: %s' % (timestamp, logconf.name, data)) def _connection_failed(self, link_uri, msg): """Callback when connection initial connection fails (i.e no Crazyflie at the speficied address)""" - print("Connection to %s failed: %s" % (link_uri, msg)) + print('Connection to %s failed: %s' % (link_uri, msg)) self.is_connected = False def _connection_lost(self, link_uri, msg): """Callback when disconnected after a connection has been made (i.e Crazyflie moves out of range)""" - print("Connection to %s lost: %s" % (link_uri, msg)) + print('Connection to %s lost: %s' % (link_uri, msg)) def _disconnected(self, link_uri): """Callback when the Crazyflie is disconnected (called in all cases)""" - print("Disconnected from %s" % link_uri) + print('Disconnected from %s' % link_uri) self.is_connected = False @@ -129,16 +126,16 @@ if __name__ == '__main__': # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=False) # Scan for Crazyflies and use the first one found - print("Scanning interfaces for Crazyflies...") + print('Scanning interfaces for Crazyflies...') available = cflib.crtp.scan_interfaces() - print("Crazyflies found:") + print('Crazyflies found:') for i in available: print(i[0]) if len(available) > 0: le = LoggingExample(available[0][0]) else: - print("No Crazyflies found, cannot run example") + print('No Crazyflies found, cannot run example') # The Crazyflie lib doesn't contain anything to keep the application alive, # so this is where your application should do something. In our case we diff --git a/examples/basicparam.py b/examples/basicparam.py index c4d252003a3cce6e75ab0f59df51778e4fe2142e..30b1d2d4e55c0f7a122ccae1f3be31c871038500 100644 --- a/examples/basicparam.py +++ b/examples/basicparam.py @@ -19,20 +19,18 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Simple example that connects to the first Crazyflie found, triggers reading of all the parameters and displays their values. It then modifies one parameter and reads back it's value. Finally it disconnects. """ import logging -import time import random +import time import cflib.crtp from cflib.crazyflie import Crazyflie @@ -59,7 +57,7 @@ class ParamExample: self._cf.connection_failed.add_callback(self._connection_failed) self._cf.connection_lost.add_callback(self._connection_lost) - print("Connecting to %s" % link_uri) + print('Connecting to %s' % link_uri) # Try to connect to the Crazyflie self._cf.open_link(link_uri) @@ -75,26 +73,26 @@ class ParamExample: def _connected(self, link_uri): """ This callback is called form the Crazyflie API when a Crazyflie has been connected and the TOCs have been downloaded.""" - print("Connected to %s" % link_uri) + print('Connected to %s' % link_uri) # Print the param TOC p_toc = self._cf.param.toc.toc for group in sorted(p_toc.keys()): - print("{}".format(group)) + print('{}'.format(group)) for param in sorted(p_toc[group].keys()): - print("\t{}".format(param)) - self._param_check_list.append("{0}.{1}".format(group, param)) - self._param_groups.append("{}".format(group)) + print('\t{}'.format(param)) + self._param_check_list.append('{0}.{1}'.format(group, param)) + self._param_groups.append('{}'.format(group)) # For every group, register the callback self._cf.param.add_update_callback(group=group, name=None, cb=self._param_callback) # You can also register a callback for a specific group.name combo - self._cf.param.add_update_callback(group="cpu", name="flash", + self._cf.param.add_update_callback(group='cpu', name='flash', cb=self._cpu_flash_callback) - print("") - print("Reading back back all parameter values") + print('') + print('Reading back back all parameter values') # Request update for all the parameters using the full name # group.name for p in self._param_check_list: @@ -102,17 +100,17 @@ class ParamExample: def _cpu_flash_callback(self, name, value): """Specific callback for the cpu.flash parameter""" - print("The connected Crazyflie has {}kb of flash".format(value)) + print('The connected Crazyflie has {}kb of flash'.format(value)) def _param_callback(self, name, value): """Generic callback registered for all the groups""" - print("{0}: {1}".format(name, value)) + print('{0}: {1}'.format(name, value)) # Remove each parameter from the list and close the link when # all are fetched self._param_check_list.remove(name) if len(self._param_check_list) == 0: - print("Have fetched all parameter values.") + print('Have fetched all parameter values.') # First remove all the group callbacks for g in self._param_groups: @@ -122,19 +120,19 @@ class ParamExample: # Create a new random value [0.00,1.00] for pid_attitude.pitch_kd # and set it pkd = random.random() - print("") - print("Write: pid_attitude.pitch_kd={:.2f}".format(pkd)) - self._cf.param.add_update_callback(group="pid_attitude", - name="pitch_kd", + print('') + print('Write: pid_attitude.pitch_kd={:.2f}'.format(pkd)) + self._cf.param.add_update_callback(group='pid_attitude', + name='pitch_kd', cb=self._a_pitch_kd_callback) # When setting a value the parameter is automatically read back # and the registered callbacks will get the updated value - self._cf.param.set_value("pid_attitude.pitch_kd", - "{:.2f}".format(pkd)) + self._cf.param.set_value('pid_attitude.pitch_kd', + '{:.2f}'.format(pkd)) def _a_pitch_kd_callback(self, name, value): """Callback for pid_attitude.pitch_kd""" - print("Readback: {0}={1}".format(name, value)) + print('Readback: {0}={1}'.format(name, value)) # End the example by closing the link (will cause the app to quit) self._cf.close_link() @@ -142,17 +140,17 @@ class ParamExample: def _connection_failed(self, link_uri, msg): """Callback when connection initial connection fails (i.e no Crazyflie at the specified address)""" - print("Connection to %s failed: %s" % (link_uri, msg)) + print('Connection to %s failed: %s' % (link_uri, msg)) self.is_connected = False def _connection_lost(self, link_uri, msg): """Callback when disconnected after a connection has been made (i.e Crazyflie moves out of range)""" - print("Connection to %s lost: %s" % (link_uri, msg)) + print('Connection to %s lost: %s' % (link_uri, msg)) def _disconnected(self, link_uri): """Callback when the Crazyflie is disconnected (called in all cases)""" - print("Disconnected from %s" % link_uri) + print('Disconnected from %s' % link_uri) self.is_connected = False @@ -160,9 +158,9 @@ if __name__ == '__main__': # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=False) # Scan for Crazyflies and use the first one found - print("Scanning interfaces for Crazyflies...") + print('Scanning interfaces for Crazyflies...') available = cflib.crtp.scan_interfaces() - print("Crazyflies found:") + print('Crazyflies found:') for i in available: print(i[0]) @@ -174,4 +172,4 @@ if __name__ == '__main__': while pe.is_connected: time.sleep(1) else: - print("No Crazyflies found, cannot run example") + print('No Crazyflies found, cannot run example') diff --git a/examples/flash-memory.py b/examples/flash-memory.py index ee1d9efdb2c169e8bfb357c8828335e2b2e7663e..ff75514645b5f63fab26a596916dc22794f43be2 100644 --- a/examples/flash-memory.py +++ b/examples/flash-memory.py @@ -11,7 +11,6 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, @@ -19,11 +18,10 @@ """ Flash the DS28E05 EEPROM via CRTP. """ - +import datetime import os import sys import time -import datetime import cflib.crtp from cflib.crazyflie import Crazyflie @@ -38,6 +36,7 @@ class Flasher(object): """ A class that can flash the DS28E05 EEPROM via CRTP. """ + def __init__(self, link_uri): self._cf = Crazyflie() self._link_uri = link_uri @@ -195,8 +194,8 @@ if __name__ == '__main__': print(' Elements: %s' % mem.elements) # Ask for new information - print("Please specify what information to write. If you just press enter, " - "the value will not be changed.") + print('Please specify what information to write. If you just press enter, ' + 'the value will not be changed.') # Vendor ID vid_input = input('New vendor ID: ') diff --git a/examples/ramp.py b/examples/ramp.py index 09d84ee9cdd06344537a605fac51877c69c58fa2..63aae005d6163a25419d2ce48fcae096a6fe2e1f 100644 --- a/examples/ramp.py +++ b/examples/ramp.py @@ -19,20 +19,17 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Simple example that connects to the first Crazyflie found, ramps up/down the motors and disconnects. """ - +import logging import time from threading import Thread -import logging import cflib from cflib.crazyflie import Crazyflie @@ -56,7 +53,7 @@ class MotorRampExample: self._cf.open_link(link_uri) - print("Connecting to %s" % link_uri) + print('Connecting to %s' % link_uri) def _connected(self, link_uri): """ This callback is called form the Crazyflie API when a Crazyflie @@ -69,16 +66,16 @@ class MotorRampExample: def _connection_failed(self, link_uri, msg): """Callback when connection initial connection fails (i.e no Crazyflie at the specified address)""" - print("Connection to %s failed: %s" % (link_uri, msg)) + print('Connection to %s failed: %s' % (link_uri, msg)) def _connection_lost(self, link_uri, msg): """Callback when disconnected after a connection has been made (i.e Crazyflie moves out of range)""" - print("Connection to %s lost: %s" % (link_uri, msg)) + print('Connection to %s lost: %s' % (link_uri, msg)) def _disconnected(self, link_uri): """Callback when the Crazyflie is disconnected (called in all cases)""" - print("Disconnected from %s" % link_uri) + print('Disconnected from %s' % link_uri) def _ramp_motors(self): thrust_mult = 1 @@ -108,13 +105,13 @@ if __name__ == '__main__': # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=False) # Scan for Crazyflies and use the first one found - print("Scanning interfaces for Crazyflies...") + print('Scanning interfaces for Crazyflies...') available = cflib.crtp.scan_interfaces() - print("Crazyflies found:") + print('Crazyflies found:') for i in available: print(i[0]) if len(available) > 0: le = MotorRampExample(available[0][0]) else: - print("No Crazyflies found, cannot run example") + print('No Crazyflies found, cannot run example') diff --git a/examples/read-eeprom.py b/examples/read-eeprom.py index 29445220bc4ca7602df6af1cd4938229b24f20ec..eea58f9014ff980cdd659eddc1f561f585b048e5 100644 --- a/examples/read-eeprom.py +++ b/examples/read-eeprom.py @@ -19,24 +19,21 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Simple example that connects to the first Crazyflie found, looks for EEPROM memories and lists its contents. """ - -import sys import logging +import sys import time import cflib.crtp -from cflib.crazyflie.mem import MemoryElement from cflib.crazyflie import Crazyflie +from cflib.crazyflie.mem import MemoryElement # Only output errors from the logging framework logging.basicConfig(level=logging.ERROR) @@ -59,7 +56,7 @@ class EEPROMExample: self._cf.connection_failed.add_callback(self._connection_failed) self._cf.connection_lost.add_callback(self._connection_lost) - print("Connecting to %s" % link_uri) + print('Connecting to %s' % link_uri) # Try to connect to the Crazyflie self._cf.open_link(link_uri) @@ -70,23 +67,23 @@ class EEPROMExample: def _connected(self, link_uri): """ This callback is called form the Crazyflie API when a Crazyflie has been connected and the TOCs have been downloaded.""" - print("Connected to %s" % link_uri) + print('Connected to %s' % link_uri) mems = self._cf.mem.get_mems(MemoryElement.TYPE_I2C) - print("Found {} EEPOM(s)".format(len(mems))) + print('Found {} EEPOM(s)'.format(len(mems))) self._mems_to_update = len(mems) for m in mems: - print("Updating id={}".format(m.id)) + print('Updating id={}'.format(m.id)) m.update(self._data_updated) def _data_updated(self, mem): - print("Updated id={}".format(mem.id)) - print("\tType : {}".format(mem.type)) - print("\tSize : {}".format(mem.size)) - print("\tValid : {}".format(mem.valid)) - print("\tElements : ") + print('Updated id={}'.format(mem.id)) + print('\tType : {}'.format(mem.type)) + print('\tSize : {}'.format(mem.size)) + print('\tValid : {}'.format(mem.valid)) + print('\tElements : ') for key in mem.elements: - print("\t\t{}={}".format(key, mem.elements[key])) + print('\t\t{}={}'.format(key, mem.elements[key])) self._mems_to_update -= 1 if self._mems_to_update == 0: @@ -94,26 +91,26 @@ class EEPROMExample: def _stab_log_error(self, logconf, msg): """Callback from the log API when an error occurs""" - print("Error when logging %s: %s" % (logconf.name, msg)) + print('Error when logging %s: %s' % (logconf.name, msg)) def _stab_log_data(self, timestamp, data, logconf): """Callback froma the log API when data arrives""" - print("[%d][%s]: %s" % (timestamp, logconf.name, data)) + print('[%d][%s]: %s' % (timestamp, logconf.name, data)) def _connection_failed(self, link_uri, msg): """Callback when connection initial connection fails (i.e no Crazyflie at the speficied address)""" - print("Connection to %s failed: %s" % (link_uri, msg)) + print('Connection to %s failed: %s' % (link_uri, msg)) self.is_connected = False def _connection_lost(self, link_uri, msg): """Callback when disconnected after a connection has been made (i.e Crazyflie moves out of range)""" - print("Connection to %s lost: %s" % (link_uri, msg)) + print('Connection to %s lost: %s' % (link_uri, msg)) def _disconnected(self, link_uri): """Callback when the Crazyflie is disconnected (called in all cases)""" - print("Disconnected from %s" % link_uri) + print('Disconnected from %s' % link_uri) self.is_connected = False @@ -121,16 +118,16 @@ if __name__ == '__main__': # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=False) # Scan for Crazyflies and use the first one found - print("Scanning interfaces for Crazyflies...") + print('Scanning interfaces for Crazyflies...') available = cflib.crtp.scan_interfaces() - print("Crazyflies found:") + print('Crazyflies found:') for i in available: print(i[0]) if len(available) > 0: le = EEPROMExample(available[0][0]) else: - print("No Crazyflies found, cannot run example") + print('No Crazyflies found, cannot run example') # The Crazyflie lib doesn't contain anything to keep the application alive, # so this is where your application should do something. In our case we diff --git a/examples/read-ow.py b/examples/read-ow.py index 7f0396834f9214c485b8874d8c74fb32834f7c2b..428d5f91552eab12f706742a5635d16374f4440c 100644 --- a/examples/read-ow.py +++ b/examples/read-ow.py @@ -19,24 +19,21 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Simple example that connects to the first Crazyflie found, looks for 1-wire memories and lists its contents. """ - -import sys import logging +import sys import time import cflib.crtp # noqa -from cflib.crazyflie.mem import MemoryElement from cflib.crazyflie import Crazyflie +from cflib.crazyflie.mem import MemoryElement # Only output errors from the logging framework logging.basicConfig(level=logging.ERROR) @@ -59,7 +56,7 @@ class OWExample: self._cf.connection_failed.add_callback(self._connection_failed) self._cf.connection_lost.add_callback(self._connection_lost) - print("Connecting to %s" % link_uri) + print('Connecting to %s' % link_uri) # Try to connect to the Crazyflie self._cf.open_link(link_uri) @@ -71,28 +68,28 @@ class OWExample: def _connected(self, link_uri): """ This callback is called form the Crazyflie API when a Crazyflie has been connected and the TOCs have been downloaded.""" - print("Connected to %s" % link_uri) + print('Connected to %s' % link_uri) mems = self._cf.mem.get_mems(MemoryElement.TYPE_1W) self._mems_to_update = len(mems) - print("Found {} 1-wire memories".format(len(mems))) + print('Found {} 1-wire memories'.format(len(mems))) for m in mems: - print("Updating id={}".format(m.id)) + print('Updating id={}'.format(m.id)) m.update(self._data_updated) def _data_updated(self, mem): - print("Updated id={}".format(mem.id)) - print("\tType : {}".format(mem.type)) - print("\tSize : {}".format(mem.size)) - print("\tValid : {}".format(mem.valid)) - print("\tName : {}".format(mem.name)) - print("\tVID : 0x{:02X}".format(mem.vid)) - print("\tPID : 0x{:02X}".format(mem.pid)) - print("\tPins : 0x{:02X}".format(mem.pins)) - print("\tElements : ") + print('Updated id={}'.format(mem.id)) + print('\tType : {}'.format(mem.type)) + print('\tSize : {}'.format(mem.size)) + print('\tValid : {}'.format(mem.valid)) + print('\tName : {}'.format(mem.name)) + print('\tVID : 0x{:02X}'.format(mem.vid)) + print('\tPID : 0x{:02X}'.format(mem.pid)) + print('\tPins : 0x{:02X}'.format(mem.pins)) + print('\tElements : ') for key in mem.elements: - print("\t\t{}={}".format(key, mem.elements[key])) + print('\t\t{}={}'.format(key, mem.elements[key])) self._mems_to_update -= 1 if self._mems_to_update == 0: @@ -100,26 +97,26 @@ class OWExample: def _stab_log_error(self, logconf, msg): """Callback from the log API when an error occurs""" - print("Error when logging %s: %s" % (logconf.name, msg)) + print('Error when logging %s: %s' % (logconf.name, msg)) def _stab_log_data(self, timestamp, data, logconf): """Callback froma the log API when data arrives""" - print("[%d][%s]: %s" % (timestamp, logconf.name, data)) + print('[%d][%s]: %s' % (timestamp, logconf.name, data)) def _connection_failed(self, link_uri, msg): """Callback when connection initial connection fails (i.e no Crazyflie at the speficied address)""" - print("Connection to %s failed: %s" % (link_uri, msg)) + print('Connection to %s failed: %s' % (link_uri, msg)) self.is_connected = False def _connection_lost(self, link_uri, msg): """Callback when disconnected after a connection has been made (i.e Crazyflie moves out of range)""" - print("Connection to %s lost: %s" % (link_uri, msg)) + print('Connection to %s lost: %s' % (link_uri, msg)) def _disconnected(self, link_uri): """Callback when the Crazyflie is disconnected (called in all cases)""" - print("Disconnected from %s" % link_uri) + print('Disconnected from %s' % link_uri) self.is_connected = False @@ -127,16 +124,16 @@ if __name__ == '__main__': # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=False) # Scan for Crazyflies and use the first one found - print("Scanning interfaces for Crazyflies...") + print('Scanning interfaces for Crazyflies...') available = cflib.crtp.scan_interfaces() - print("Crazyflies found:") + print('Crazyflies found:') for i in available: print(i[0]) if len(available) > 0: le = OWExample(available[0][0]) else: - print("No Crazyflies found, cannot run example") + print('No Crazyflies found, cannot run example') # The Crazyflie lib doesn't contain anything to keep the application alive, # so this is where your application should do something. In our case we diff --git a/examples/scan.py b/examples/scan.py index c298b47e4f6fd64ecca0666cc4d291aa3b42cffe..06e0c8143e0ac63fa0ceb803d2354a8557430b7c 100644 --- a/examples/scan.py +++ b/examples/scan.py @@ -19,23 +19,20 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Simple example that scans for available Crazyflies and lists them. """ - import cflib.crtp # Initiate the low level drivers cflib.crtp.init_drivers(enable_debug_driver=False) -print("Scanning interfaces for Crazyflies...") +print('Scanning interfaces for Crazyflies...') available = cflib.crtp.scan_interfaces() -print("Crazyflies found:") +print('Crazyflies found:') for i in available: print(i[0]) diff --git a/examples/write-eeprom.py b/examples/write-eeprom.py index 9b1df7ffe2a746ba673e3f2a9247c91936ef7136..76a840358539fdb853a9897b59030a7a969f4580 100644 --- a/examples/write-eeprom.py +++ b/examples/write-eeprom.py @@ -19,24 +19,21 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Simple example that connects to the first Crazyflie found, looks for EEPROM memories and writes the default values in it. """ - -import sys import logging +import sys import time import cflib.crtp -from cflib.crazyflie.mem import MemoryElement from cflib.crazyflie import Crazyflie +from cflib.crazyflie.mem import MemoryElement # Only output errors from the logging framework logging.basicConfig(level=logging.ERROR) @@ -60,7 +57,7 @@ class EEPROMExample: self._cf.connection_failed.add_callback(self._connection_failed) self._cf.connection_lost.add_callback(self._connection_lost) - print("Connecting to %s" % link_uri) + print('Connecting to %s' % link_uri) # Try to connect to the Crazyflie self._cf.open_link(link_uri) @@ -71,61 +68,61 @@ class EEPROMExample: def _connected(self, link_uri): """ This callback is called form the Crazyflie API when a Crazyflie has been connected and the TOCs have been downloaded.""" - print("Connected to %s" % link_uri) + print('Connected to %s' % link_uri) mems = self._cf.mem.get_mems(MemoryElement.TYPE_I2C) - print("Found {} EEPOM(s)".format(len(mems))) + print('Found {} EEPOM(s)'.format(len(mems))) if len(mems) > 0: - print("Writing default configuration to" - " memory {}".format(mems[0].id)) + print('Writing default configuration to' + ' memory {}'.format(mems[0].id)) elems = mems[0].elements - elems["version"] = 1 - elems["pitch_trim"] = 0.0 - elems["roll_trim"] = 0.0 - elems["radio_channel"] = 80 - elems["radio_speed"] = 0 - elems["radio_address"] = 0xE7E7E7E7E7 + elems['version'] = 1 + elems['pitch_trim'] = 0.0 + elems['roll_trim'] = 0.0 + elems['radio_channel'] = 80 + elems['radio_speed'] = 0 + elems['radio_address'] = 0xE7E7E7E7E7 mems[0].write_data(self._data_written) def _data_written(self, mem, addr): - print("Data written, reading back...") - mem.update(self._data_updated) + print('Data written, reading back...') + mem.update(self._data_updated) def _data_updated(self, mem): - print("Updated id={}".format(mem.id)) - print("\tType : {}".format(mem.type)) - print("\tSize : {}".format(mem.size)) - print("\tValid : {}".format(mem.valid)) - print("\tElements : ") + print('Updated id={}'.format(mem.id)) + print('\tType : {}'.format(mem.type)) + print('\tSize : {}'.format(mem.size)) + print('\tValid : {}'.format(mem.valid)) + print('\tElements : ') for key in mem.elements: - print("\t\t{}={}".format(key, mem.elements[key])) + print('\t\t{}={}'.format(key, mem.elements[key])) self._cf.close_link() def _stab_log_error(self, logconf, msg): """Callback from the log API when an error occurs""" - print("Error when logging %s: %s" % (logconf.name, msg)) + print('Error when logging %s: %s' % (logconf.name, msg)) def _stab_log_data(self, timestamp, data, logconf): """Callback froma the log API when data arrives""" - print("[%d][%s]: %s" % (timestamp, logconf.name, data)) + print('[%d][%s]: %s' % (timestamp, logconf.name, data)) def _connection_failed(self, link_uri, msg): """Callback when connection initial connection fails (i.e no Crazyflie at the speficied address)""" - print("Connection to %s failed: %s" % (link_uri, msg)) + print('Connection to %s failed: %s' % (link_uri, msg)) self.is_connected = False def _connection_lost(self, link_uri, msg): """Callback when disconnected after a connection has been made (i.e Crazyflie moves out of range)""" - print("Connection to %s lost: %s" % (link_uri, msg)) + print('Connection to %s lost: %s' % (link_uri, msg)) def _disconnected(self, link_uri): """Callback when the Crazyflie is disconnected (called in all cases)""" - print("Disconnected from %s" % link_uri) + print('Disconnected from %s' % link_uri) self.is_connected = False @@ -133,16 +130,16 @@ if __name__ == '__main__': # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=True) # Scan for Crazyflies and use the first one found - print("Scanning interfaces for Crazyflies...") + print('Scanning interfaces for Crazyflies...') available = cflib.crtp.scan_interfaces() - print("Crazyflies found:") + print('Crazyflies found:') for i in available: print(i[0]) if len(available) > 0: le = EEPROMExample(available[0][0]) else: - print("No Crazyflies found, cannot run example") + print('No Crazyflies found, cannot run example') # The Crazyflie lib doesn't contain anything to keep the application alive, # so this is where your application should do something. In our case we diff --git a/examples/write-ow.py b/examples/write-ow.py index ae2b8c94dd48891ce81f84e4ee649b95a01ea5ec..5b1af6209b01c1e2326741c9b500a5bd2a50ce18 100644 --- a/examples/write-ow.py +++ b/examples/write-ow.py @@ -19,24 +19,22 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - """ Simple example that connects to the first Crazyflie found, looks for EEPROM memories and lists its contents. """ - -import sys import logging +import sys import time import cflib.crtp -from cflib.crazyflie.mem import MemoryElement, OWElement from cflib.crazyflie import Crazyflie +from cflib.crazyflie.mem import MemoryElement +from cflib.crazyflie.mem import OWElement # Only output errors from the logging framework logging.basicConfig(level=logging.ERROR) @@ -59,7 +57,7 @@ class EEPROMExample: self._cf.connection_failed.add_callback(self._connection_failed) self._cf.connection_lost.add_callback(self._connection_lost) - print("Connecting to %s" % link_uri) + print('Connecting to %s' % link_uri) # Try to connect to the Crazyflie self._cf.open_link(link_uri) @@ -70,13 +68,13 @@ class EEPROMExample: def _connected(self, link_uri): """ This callback is called form the Crazyflie API when a Crazyflie has been connected and the TOCs have been downloaded.""" - print("Connected to %s" % link_uri) + print('Connected to %s' % link_uri) mems = self._cf.mem.get_mems(MemoryElement.TYPE_1W) - print("Found {} 1-wire memories".format(len(mems))) + print('Found {} 1-wire memories'.format(len(mems))) if len(mems) > 0: - print("Writing test configuration to" - " memory {}".format(mems[0].id)) + print('Writing test configuration to' + ' memory {}'.format(mems[0].id)) mems[0].vid = 0xBC mems[0].pid = 0xFF @@ -84,73 +82,73 @@ class EEPROMExample: board_name_id = OWElement.element_mapping[1] board_rev_id = OWElement.element_mapping[2] - mems[0].elements[board_name_id] = "Test board" - mems[0].elements[board_rev_id] = "A" + mems[0].elements[board_name_id] = 'Test board' + mems[0].elements[board_rev_id] = 'A' mems[0].write_data(self._data_written) def _data_written(self, mem, addr): - print("Data written, reading back...") - mem.update(self._data_updated) + print('Data written, reading back...') + mem.update(self._data_updated) def _data_updated(self, mem): - print("Updated id={}".format(mem.id)) - print("\tType : {}".format(mem.type)) - print("\tSize : {}".format(mem.size)) - print("\tValid : {}".format(mem.valid)) - print("\tName : {}".format(mem.name)) - print("\tVID : 0x{:02X}".format(mem.vid)) - print("\tPID : 0x{:02X}".format(mem.pid)) - print("\tPins : 0x{:02X}".format(mem.pins)) - print("\tElements : ") + print('Updated id={}'.format(mem.id)) + print('\tType : {}'.format(mem.type)) + print('\tSize : {}'.format(mem.size)) + print('\tValid : {}'.format(mem.valid)) + print('\tName : {}'.format(mem.name)) + print('\tVID : 0x{:02X}'.format(mem.vid)) + print('\tPID : 0x{:02X}'.format(mem.pid)) + print('\tPins : 0x{:02X}'.format(mem.pins)) + print('\tElements : ') for key in mem.elements: - print("\t\t{}={}".format(key, mem.elements[key])) + print('\t\t{}={}'.format(key, mem.elements[key])) self._cf.close_link() def _stab_log_error(self, logconf, msg): """Callback from the log API when an error occurs""" - print("Error when logging %s: %s" % (logconf.name, msg)) + print('Error when logging %s: %s' % (logconf.name, msg)) def _stab_log_data(self, timestamp, data, logconf): """Callback froma the log API when data arrives""" - print("[%d][%s]: %s" % (timestamp, logconf.name, data)) + print('[%d][%s]: %s' % (timestamp, logconf.name, data)) def _connection_failed(self, link_uri, msg): """Callback when connection initial connection fails (i.e no Crazyflie at the speficied address)""" - print("Connection to %s failed: %s" % (link_uri, msg)) + print('Connection to %s failed: %s' % (link_uri, msg)) self.is_connected = False def _connection_lost(self, link_uri, msg): """Callback when disconnected after a connection has been made (i.e Crazyflie moves out of range)""" - print("Connection to %s lost: %s" % (link_uri, msg)) + print('Connection to %s lost: %s' % (link_uri, msg)) def _disconnected(self, link_uri): """Callback when the Crazyflie is disconnected (called in all cases)""" - print("Disconnected from %s" % link_uri) + print('Disconnected from %s' % link_uri) self.is_connected = False if __name__ == '__main__': - print("This example will not work with the BLE version of the nRF51" - " firmware (flashed on production units). See https://github.com" - "/bitcraze/crazyflie-clients-python/issues/166") + print('This example will not work with the BLE version of the nRF51' + ' firmware (flashed on production units). See https://github.com' + '/bitcraze/crazyflie-clients-python/issues/166') # Initialize the low-level drivers (don't list the debug drivers) cflib.crtp.init_drivers(enable_debug_driver=True) # Scan for Crazyflies and use the first one found - print("Scanning interfaces for Crazyflies...") + print('Scanning interfaces for Crazyflies...') available = cflib.crtp.scan_interfaces() - print("Crazyflies found:") + print('Crazyflies found:') for i in available: print(i[0]) if len(available) > 0: le = EEPROMExample(available[0][0]) else: - print("No Crazyflies found, cannot run example") + print('No Crazyflies found, cannot run example') # The Crazyflie lib doesn't contain anything to keep the application alive, # so this is where your application should do something. In our case we diff --git a/setup.py b/setup.py index 64863b7f7774de1c842550473042b0bc9b55a275..5b409e0e04c3e207e1de08f9a73675302b90df08 100644 --- a/setup.py +++ b/setup.py @@ -2,22 +2,22 @@ from setuptools import setup setup( - name="cflib", - version="0.1.0", - packages=["cflib"], + name='cflib', + version='0.1.0', + packages=['cflib'], - description="Crazyflie python driver", - url="https://github.com/bitcraze/crazyflie-lib-python", + description='Crazyflie python driver', + url='https://github.com/bitcraze/crazyflie-lib-python', - author="Bitcraze and contributors", - license="GPLv3", + author='Bitcraze and contributors', + license='GPLv3', classifiers=[ - "Development Status :: 4 - Beta", - "License :: OSI Approved :: GNU General Public License v3 (GPLv3)", - "Topic :: System :: Hardware :: Hardware Drivers", - "Programming Language :: Python :: 2", - "Programming Language :: Python :: 3" + 'Development Status :: 4 - Beta', + 'License :: OSI Approved :: GNU General Public License v3 (GPLv3)', + 'Topic :: System :: Hardware :: Hardware Drivers', + 'Programming Language :: Python :: 2', + 'Programming Language :: Python :: 3' ], keywords='driver crazyflie quadcopter', diff --git a/setup_linux.sh b/setup_linux.sh index 648265d533075a717f332a153f8dbf214a9a1bfa..9ea51d5f6f035795bd682d2ccf14fe2183415647 100755 --- a/setup_linux.sh +++ b/setup_linux.sh @@ -18,4 +18,3 @@ MODE=\"0664\", GROUP=\"plugdev\" > /etc/udev/rules.d/99-crazyflie.rules # Install Crazyflie PC client python3 setup.py install - diff --git a/test/crtp/test_crtpstack.py b/test/crtp/test_crtpstack.py index 1c45422e5bf1ceef8b546a915b59c12592c195a4..903032da46e8bc47020bb3109f9e439540daff93 100644 --- a/test/crtp/test_crtpstack.py +++ b/test/crtp/test_crtpstack.py @@ -19,12 +19,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - import unittest from cflib.crtp.crtpstack import CRTPPacket diff --git a/test/utils/test_callbacks.py b/test/utils/test_callbacks.py index 649d4bd1aa1307207523885e761b08bab905b730..bd00a0800bc85edfc48725df8543850470e10994 100644 --- a/test/utils/test_callbacks.py +++ b/test/utils/test_callbacks.py @@ -19,12 +19,10 @@ # but WITHOUT ANY WARRANTY; without even the implied warranty of # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # GNU General Public License for more details. - # You should have received a copy of the GNU General Public License # along with this program; if not, write to the Free Software # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, # MA 02110-1301, USA. - import unittest from cflib.utils.callbacks import Caller