Skip to content

Commit

Permalink
IMPROVEMENTS: pylint fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed Apr 29, 2024
1 parent b2f8f0b commit 8010315
Show file tree
Hide file tree
Showing 2 changed files with 38 additions and 30 deletions.
35 changes: 15 additions & 20 deletions MethodicConfigurator/backend_mavftp.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,10 @@
try:
from pymavlink import mavutil
from pymavlink import mavparm
except Exception:
except ImportError:
pass


# pylint: disable=invalid-name
# opcodes
OP_None = 0
OP_TerminateSession = 1
Expand Down Expand Up @@ -70,10 +70,11 @@

HDR_Len = 12
MAX_Payload = 239
# pylint: enable=invalid-name


class FTP_OP:
def __init__(self, seq, session, opcode, size, req_opcode, burst_complete, offset, payload):
class FTP_OP: # pylint: disable=missing-class-docstring, invalid-name, too-many-instance-attributes
def __init__(self, seq, session, opcode, size, # pylint: disable=too-many-arguments
req_opcode, burst_complete, offset, payload):
self.seq = seq
self.session = session
self.opcode = opcode
Expand All @@ -96,27 +97,21 @@ def __str__(self):
plen = 0
if self.payload is not None:
plen = len(self.payload)
ret = "OP seq:%u sess:%u opcode:%d req_opcode:%u size:%u bc:%u ofs:%u plen=%u" % (self.seq,
self.session,
self.opcode,
self.req_opcode,
self.size,
self.burst_complete,
self.offset,
plen)
ret = f"OP seq:{self.seq} sess:{self.session} opcode:{self.opcode} req_opcode:{self.req_opcode}" \
f" size:{self.size} bc:{self.burst_complete} ofs:{self.offset} plen={plen}"
if plen > 0:
ret += " [%u]" % self.payload[0]
ret += f" [{self.payload[0]}]"
return ret


class WriteQueue:
class WriteQueue: # pylint: disable=missing-class-docstring, too-few-public-methods
def __init__(self, ofs, size):
self.ofs = ofs
self.size = size
self.last_send = 0


class MAVFTP:
class MAVFTP: # pylint: disable=missing-class-docstring, too-many-instance-attributes
def __init__(self):
self.ftp_settings_debug = 2
self.ftp_settings_pkt_loss_rx = 0
Expand Down Expand Up @@ -154,7 +149,7 @@ def __init__(self):
self.ftp_failed = False
self.mav_param_set = set()
self.param_types = {}
self.fetch_one = dict()
self.fetch_one = {}
self.fetch_set = None
self.mav_param = mavparm.MAVParmDict()
self.mav_param_count = 0
Expand All @@ -173,7 +168,7 @@ def send(self, op):
self.last_op = op
now = time_time()
if self.ftp_settings_debug > 1:
logging_info("> %s dt=%.2f" % (op, now - self.last_op_time))
logging_info("> %s dt=%.2f", op, now - self.last_op_time)
self.last_op_time = time_time()

def terminate_session(self):
Expand Down Expand Up @@ -298,7 +293,7 @@ def ftp_callback(self, fh):

self.param_types = {}
self.mav_param_set = set()
self.fetch_one = dict()
self.fetch_one = {}
self.fetch_set = None
self.mav_param.clear()
total_params = len(pdata.params)
Expand Down Expand Up @@ -459,7 +454,7 @@ def check_read_finished(self):
return True
return False

def handle_burst_read(self, op, m):
def handle_burst_read(self, op, m): # pylint: disable=too-many-branches, too-many-statements, too-many-return-statements
'''handle OP_BurstReadFile reply'''
if self.ftp_settings_pkt_loss_tx > 0:
if random_uniform(0, 100) < self.ftp_settings_pkt_loss_tx:
Expand Down
33 changes: 23 additions & 10 deletions MethodicConfigurator/param_ftp.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,23 @@
#!/usr/bin/env python3
'''
decode ftp parameter protocol data
'''
Original file was part of MAVProxy
This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator
# pylint: skip-file
(C) 2024 Amilcar do Carmo Lucas, IAV GmbH
SPDX-License-Identifier: GPL-3
'''

import struct
import sys


class ParamData(object):
class ParamData():
"""
A class to manage parameter values and defaults for ArduPilot configuration.
"""
def __init__(self):
# params as (name, value, ptype)
self.params = []
Expand All @@ -25,7 +33,7 @@ def add_default(self, name, value, ptype):
self.defaults.append((name, value, ptype))


def ftp_param_decode(data):
def ftp_param_decode(data): # pylint: disable=too-many-locals, too-many-branches
'''decode parameter data, returning ParamData'''
pdata = ParamData()

Expand All @@ -34,7 +42,7 @@ def ftp_param_decode(data):
if len(data) < 6:
return None
magic2, _num_params, total_params = struct.unpack("<HHH", data[0:6])
if magic != magic2 and magic_defaults != magic2:
if magic2 not in (magic, magic_defaults):
print("paramftp: bad magic 0x%x expected 0x%x", magic2, magic)
return None
with_defaults = magic2 == magic_defaults
Expand Down Expand Up @@ -78,7 +86,7 @@ def ftp_param_decode(data):
default_len = type_len if has_default else 0

name_len = ((plen >> 4) & 0x0F) + 1
common_len = (plen & 0x0F)
common_len = plen & 0x0F
name = last_name[0:common_len] + data[2:2+name_len]
vdata = data[2+name_len:2+name_len+type_len+default_len]
last_name = name
Expand All @@ -104,13 +112,18 @@ def ftp_param_decode(data):
return pdata


if __name__ == "__main__":
def main():
fname = sys.argv[1]
data = open(fname, 'rb').read()
print("Decoding file of length %u" % len(data))
with open(fname, 'rb') as file:
data = file.read()
print(f"Decoding file of length {len(data)}")
pdata = ftp_param_decode(data)
if pdata is None:
print("Decode failed")
sys.exit(1)
for (name, value, ptype) in pdata.params:
for (name, value, _ptype) in pdata.params:
print(name.decode('utf-8'), value)


if __name__ == "__main__":
main()

0 comments on commit 8010315

Please sign in to comment.