From 899d8c4d12c1897cc0d0842dd67b148799e1f476 Mon Sep 17 00:00:00 2001 From: Thomas David Date: Wed, 28 Feb 2024 06:50:43 +0000 Subject: [PATCH 1/2] replaced print statements with logger.info --- mavextra.py | 7 ++++--- mavparm.py | 33 +++++++++++++++++---------------- mavutil.py | 46 ++++++++++++++++++++++++---------------------- mavwp.py | 18 ++++++++++-------- 4 files changed, 55 insertions(+), 49 deletions(-) diff --git a/mavextra.py b/mavextra.py index 0b0ee8662..2067a1ecb 100644 --- a/mavextra.py +++ b/mavextra.py @@ -9,7 +9,8 @@ from __future__ import absolute_import from builtins import object from builtins import sum as builtin_sum - +import logging +logger = logging.getLogger('pymavlink') from math import * try: @@ -573,7 +574,7 @@ def distance_two(MSG1, MSG2, horizontal=True): try: return _distance_two(MSG1, MSG2) except Exception as ex: - print(ex) + logger.info(ex) return None first_fix = None @@ -620,7 +621,7 @@ def airspeed(VFR_HUD, ratio=None, used_ratio=None, offset=None): if 'ARSPD_RATIO' in mav.params: used_ratio = mav.params['ARSPD_RATIO'] else: - print("no ARSPD_RATIO in mav.params") + logger.info("no ARSPD_RATIO in mav.params") used_ratio = ratio if hasattr(VFR_HUD,'airspeed'): airspeed = VFR_HUD.airspeed diff --git a/mavparm.py b/mavparm.py index f89cc8164..a0e05384b 100644 --- a/mavparm.py +++ b/mavparm.py @@ -6,7 +6,8 @@ import fnmatch, math, time, struct from pymavlink import mavutil - +import logging +logger = logging.getLogger('pymavlink') class MAVParmDict(dict): def __init__(self, *args): dict.__init__(self, args) @@ -46,7 +47,7 @@ def mavset(self, mav, name, value, retries=3, parm_type=None): elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_INT32: vstr = struct.pack(">i", int(value)) else: - print("can't send %s of type %u" % (name, parm_type)) + logger.info("can't send %s of type %u" % (name, parm_type)) return False numeric_value, = struct.unpack(">f", vstr) else: @@ -69,7 +70,7 @@ def mavset(self, mav, name, value, retries=3, parm_type=None): self.__setitem__(name, numeric_value) break if not got_ack: - print("timeout setting %s to %f" % (name, numeric_value)) + logger.info("timeout setting %s to %f" % (name, numeric_value)) return False return True @@ -90,7 +91,7 @@ def save(self, filename, wildcard='*', verbose=False): count += 1 f.close() if verbose: - print("Saved %u parameters to %s" % (count, filename)) + logger.info("Saved %u parameters to %s" % (count, filename)) def load(self, filename, wildcard='*', mav=None, check=True, use_excludes=True): @@ -98,7 +99,7 @@ def load(self, filename, wildcard='*', mav=None, check=True, use_excludes=True): try: f = open(filename, mode='r') except Exception as e: - print("Failed to open file '%s': %s" % (filename, str(e))) + logger.info("Failed to open file '%s': %s" % (filename, str(e))) return False count = 0 changed = 0 @@ -109,7 +110,7 @@ def load(self, filename, wildcard='*', mav=None, check=True, use_excludes=True): line = line.replace(',',' ') a = line.split() if len(a) != 2: - print("Invalid line: %s" % line) + logger.info("Invalid line: %s" % line) continue # some parameters should not be loaded from files if use_excludes and a[0] in self.exclude_load: @@ -125,16 +126,16 @@ def load(self, filename, wildcard='*', mav=None, check=True, use_excludes=True): if mav is not None: if check: if a[0] not in list(self.keys()): - print("Unknown parameter %s" % a[0]) + logger.info("Unknown parameter %s" % a[0]) continue old_value = self.__getitem__(a[0]) if math.fabs(old_value - numeric_value) <= self.mindelta: count += 1 continue if self.mavset(mav, a[0], value): - print("changed %s from %f to %f" % (a[0], old_value, numeric_value)) + logger.info("changed %s from %f to %f" % (a[0], old_value, numeric_value)) else: - print("set %s to %f" % (a[0], numeric_value)) + logger.info("set %s to %f" % (a[0], numeric_value)) self.mavset(mav, a[0], value) changed += 1 else: @@ -142,13 +143,13 @@ def load(self, filename, wildcard='*', mav=None, check=True, use_excludes=True): count += 1 f.close() if mav is not None: - print("Loaded %u parameters from %s (changed %u)" % (count, filename, changed)) + logger.info("Loaded %u parameters from %s (changed %u)" % (count, filename, changed)) else: - print("Loaded %u parameters from %s" % (count, filename)) + logger.info("Loaded %u parameters from %s" % (count, filename)) return True def show_param_value(self, name, value): - print("%-16.16s %s" % (name, value)) + logger.info("%-16.16s %s" % (name, value)) def show(self, wildcard='*'): '''show parameters''' @@ -169,13 +170,13 @@ def diff(self, filename, wildcard='*', use_excludes=True, use_tabs=False, show_o if not k in other: value = float(self[k]) if show_only2: - print("%-16.16s %12.4f" % (k, value)) + logger.info("%-16.16s %12.4f" % (k, value)) elif not k in self: if show_only1: - print("%-16.16s %12.4f" % (k, float(other[k]))) + logger.info("%-16.16s %12.4f" % (k, float(other[k]))) elif abs(self[k] - other[k]) > self.mindelta: value = float(self[k]) if use_tabs: - print("%s\t%.4f\t%.4f" % (k, other[k], value)) + logger.info("%s\t%.4f\t%.4f" % (k, other[k], value)) else: - print("%-16.16s %12.4f %12.4f" % (k, other[k], value)) + logger.info("%-16.16s %12.4f %12.4f" % (k, other[k], value)) diff --git a/mavutil.py b/mavutil.py index aff3ce882..28ce7dea8 100644 --- a/mavutil.py +++ b/mavutil.py @@ -15,6 +15,8 @@ import re import platform from pymavlink import mavexpression +import logging +logger = logging.getLogger('pymavlink') # We want to re-export x25crc here from pymavlink.generator.mavcrc import x25crc as x25crc @@ -410,7 +412,7 @@ def post_message(self, msg): if seq != seq2 and last_seq != -1: diff = (seq2 - seq) % 256 self.mav_loss += diff - #print("lost %u seq=%u seq2=%u last_seq=%u src_tupe=%s %s" % (diff, seq, seq2, last_seq, str(src_tuple), msg.get_type())) + #logger.info("lost %u seq=%u seq2=%u last_seq=%u src_tupe=%s %s" % (diff, seq, seq2, last_seq, str(src_tuple), msg.get_type())) self.last_seq[src_tuple] = seq2 self.mav_count += 1 @@ -654,7 +656,7 @@ def set_mode_flag(self, flag, enable): mode, 0, 0, 0, 0, 0, 0) else: - print("Set mode flag not supported") + logger.info("Set mode flag not supported") def set_mode_auto(self): '''enter auto mode''' @@ -680,7 +682,7 @@ def set_mode_apm(self, mode, custom_mode = 0, custom_sub_mode = 0): if isinstance(mode, str): mode_map = self.mode_mapping() if mode_map is None or mode not in mode_map: - print("Unknown mode '%s'" % mode) + logger.info("Unknown mode '%s'" % mode) return mode = mode_map[mode] # set mode by integer mode number for ArduPilot @@ -701,7 +703,7 @@ def set_mode_px4(self, mode, custom_mode, custom_sub_mode): if isinstance(mode, str): mode_map = self.mode_mapping() if mode_map is None or mode not in mode_map: - print("Unknown mode '%s'" % mode) + logger.info("Unknown mode '%s'" % mode) return # PX4 uses two fields to define modes mode, custom_mode, custom_sub_mode = px4_map[mode] @@ -744,7 +746,7 @@ def set_mode_fbwa(self): mavlink.MAV_MODE_STABILIZE_ARMED, 0, 0, 0, 0, 0, 0) else: - print("Forcing FBWA not supported") + logger.info("Forcing FBWA not supported") def set_mode_loiter(self): '''enter LOITER mode''' @@ -779,7 +781,7 @@ def set_relay(self, relay_pin=0, state=True): 0, # param6 0) # param7 else: - print("Setting relays not supported.") + logger.info("Setting relays not supported.") def calibrate_level(self): '''calibrate accels (1D version)''' @@ -1015,7 +1017,7 @@ def write(self, buf): return self.port.write(bytes(buf)) except Exception: if not self.portdead: - print("Device %s is dead" % self.device) + logger.info("Device %s is dead" % self.device) self.portdead = True if self.autoreconnect: self.reset() @@ -1034,7 +1036,7 @@ def reset(self): return False self.port.close() self.port = newport - print("Device %s reopened OK" % self.device) + logger.info("Device %s reopened OK" % self.device) self.portdead = False try: self.fd = self.port.fileno() @@ -1053,7 +1055,7 @@ class mavudp(mavfile): def __init__(self, device, input=True, broadcast=False, source_system=255, source_component=0, use_native=default_native, timeout=0): a = device.split(':') if len(a) != 2: - print("UDP ports must be specified as host:port") + logger.info("UDP ports must be specified as host:port") sys.exit(1) self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) self.udp_server = input @@ -1225,7 +1227,7 @@ def __init__(self, use_native=default_native): a = device.split(':') if len(a) != 2: - print("TCP ports must be specified as host:port") + logger.info("TCP ports must be specified as host:port") sys.exit(1) self.destination_addr = (a[0], int(a[1])) @@ -1256,7 +1258,7 @@ def do_connect(self): self.port.close() self.port = None raise e - print(e, "sleeping") + logger.info(f"{e} sleeping") time.sleep(1) self.port.setblocking(0) set_close_on_exec(self.port.fileno()) @@ -1266,12 +1268,12 @@ def close(self): self.port.close() def handle_disconnect(self): - print("Connection reset or closed by peer on TCP socket") + logger.info("Connection reset or closed by peer on TCP socket") self.reconnect() def handle_eof(self): # EOF - print("EOF on TCP socket") + logger.info("EOF on TCP socket") self.reconnect() def recv(self,n=None): @@ -1309,7 +1311,7 @@ def write(self, buf): def reconnect(self): if self.autoreconnect: - print("Attempting reconnect") + logger.info("Attempting reconnect") if self.port is not None: self.port.close() self.port = None @@ -1321,7 +1323,7 @@ class mavtcpin(mavfile): def __init__(self, device, source_system=255, source_component=0, retries=3, use_native=default_native): a = device.split(':') if len(a) != 2: - print("TCP ports must be specified as host:port") + logger.info("TCP ports must be specified as host:port") sys.exit(1) self.listen = socket.socket(socket.AF_INET, socket.SOCK_STREAM) self.listen_addr = (a[0], int(a[1])) @@ -1813,7 +1815,7 @@ def mavlink_connection(device, baud=115200, source_system=255, source_component= return mavudp(device, source_system=source_system, source_component=source_component, input=input, use_native=use_native) if os.path.isfile(device): if device.endswith(".elf") or device.find("/bin/") != -1: - print("executing '%s'" % device) + logger.info("executing '%s'" % device) return mavchildexec(device, source_system=source_system, source_component=source_component, use_native=use_native) elif not write and not append and not notimestamps: return mavmmaplog(device, progress_callback=progress_callback) @@ -1844,7 +1846,7 @@ def trigger(self): tnow = time.time() if tnow < self.last_time: - print("Warning, time moved backwards. Restarting timer.") + logger.info("Warning, time moved backwards. Restarting timer.") self.last_time = tnow if self.last_time + (1.0/self.frequency) <= tnow: @@ -2153,7 +2155,7 @@ def mode_string_v09(msg): _json_mode_map = json.load(f) except json.decoder.JSONDecodeError as ex: # inform the user of a malformed custom_mode_map.json - print("Error: pymavlink custom mode file ('" + _custom_mode_map_path + "') is not valid JSON.") + logger.info("Error: pymavlink custom mode file ('" + _custom_mode_map_path + "') is not valid JSON.") raise except Exception: # file is not present, fall back to using default map @@ -2166,7 +2168,7 @@ def mode_string_v09(msg): _custom_mode_map[int(mav_type)] = { int(mode_num): str(mode_name) for mode_num, mode_name in mode_map.items() } except Exception: # inform the user of invalid custom mode map - print("Error: invalid pymavlink custom mode map dict in " + _custom_mode_map_path) + logger.info("Error: invalid pymavlink custom mode map dict in " + _custom_mode_map_path) raise AP_MAV_TYPE_MODE_MAP = AP_MAV_TYPE_MODE_MAP_DEFAULT.copy() @@ -2341,7 +2343,7 @@ def __init__(self, portname, baudrate, devnum=0, devbaud=0, timeout=3, debug=0): def debug(self, s, level=1): '''write some debug text''' if self._debug >= level: - print(s) + logger.info(s) def write(self, b): '''write some bytes''' @@ -2382,7 +2384,7 @@ def _recv(self): break if m is not None: if self._debug > 2: - print(m) + logger.info(m) data = m.data[:m.count] self.buf.extend(data) @@ -2589,4 +2591,4 @@ def dump_message_verbose(f, m): if __name__ == '__main__': serial_list = auto_detect_serial(preferred_list=['*FTDI*',"*Arduino_Mega_2560*", "*3D_Robotics*", "*USB_to_UART*", '*PX4*', '*FMU*']) for port in serial_list: - print("%s" % port) + logger.info("%s" % port) diff --git a/mavwp.py b/mavwp.py index 6906afaad..e0d14a934 100644 --- a/mavwp.py +++ b/mavwp.py @@ -9,9 +9,11 @@ from builtins import object import time, copy -import logging import re +import logging +logger = logging.getLogger('pymavlink') + from . import mavutil try: from google.protobuf import text_format @@ -524,7 +526,7 @@ def load(self, filename): # at least 3 vertex points # 1 closing point if len(points) < 5: - print("Insufficient points in file") + logger.info("Insufficient points in file") return items = [] @@ -673,7 +675,7 @@ def reindex(self): def append_rally_point(self, p): '''add rallypoint to end of list''' if (self.rally_count() > 9): - print("Can't have more than 10 rally points, not adding.") + logger.info("Can't have more than 10 rally points, not adding.") return self.rally_points.append(p) @@ -693,14 +695,14 @@ def clear(self): def remove(self, i): '''remove a rally point''' if i < 1 or i > self.rally_count(): - print("Invalid rally point number %u" % i) + logger.info("Invalid rally point number %u" % i) self.rally_points.pop(i-1) self.reindex() def move(self, i, lat, lng, change_time=True): '''move a rally point''' if i < 1 or i > self.rally_count(): - print("Invalid rally point number %u" % i) + logger.info("Invalid rally point number %u" % i) self.rally_points[i-1].lat = int(lat*1e7) self.rally_points[i-1].lng = int(lng*1e7) if change_time: @@ -709,7 +711,7 @@ def move(self, i, lat, lng, change_time=True): def set_alt(self, i, alt, break_alt=None, change_time=True): '''set rally point altitude(s)''' if i < 1 or i > self.rally_count(): - print("Invalid rally point number %u" % i) + logger.info("Invalid rally point number %u" % i) return self.rally_points[i-1].alt = int(alt) if break_alt is not None: @@ -822,7 +824,7 @@ def save(self, filename): def move(self, i, lat, lng, change_time=True): '''move a fence point''' if i < 0 or i >= self.count(): - print("Invalid fence point number %u" % i) + logger.info("Invalid fence point number %u" % i) self.points[i].lat = lat self.points[i].lng = lng # ensure we close the polygon @@ -838,7 +840,7 @@ def move(self, i, lat, lng, change_time=True): def remove(self, i, change_time=True): '''remove a fence point''' if i < 0 or i >= self.count(): - print("Invalid fence point number %u" % i) + logger.info("Invalid fence point number %u" % i) self.points.pop(i) # ensure we close the polygon if i == 1: From 864e2a1b380566e54ace331d03fbd6abf009a9e4 Mon Sep 17 00:00:00 2001 From: Thomas David Date: Wed, 28 Feb 2024 06:56:07 +0000 Subject: [PATCH 2/2] py35 fix --- mavutil.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavutil.py b/mavutil.py index 28ce7dea8..2d63a0a94 100644 --- a/mavutil.py +++ b/mavutil.py @@ -1258,7 +1258,7 @@ def do_connect(self): self.port.close() self.port = None raise e - logger.info(f"{e} sleeping") + logger.info(str(e) + " sleeping") time.sleep(1) self.port.setblocking(0) set_close_on_exec(self.port.fileno())