Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Replace print statements with python standard library logging #924

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions mavextra.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
33 changes: 17 additions & 16 deletions mavparm.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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:
Expand All @@ -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

Expand All @@ -90,15 +91,15 @@ 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):
'''load parameters from a file'''
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
Expand All @@ -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:
Expand All @@ -125,30 +126,30 @@ 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:
self.__setitem__(a[0], numeric_value)
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'''
Expand All @@ -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))
42 changes: 23 additions & 19 deletions mavutil.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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'''
Expand All @@ -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
Expand All @@ -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]
Expand Down Expand Up @@ -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'''
Expand Down Expand Up @@ -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)'''
Expand Down Expand Up @@ -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()
Expand All @@ -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()
Expand Down Expand Up @@ -1225,6 +1227,7 @@ def __init__(self,
a = device.split(':')
if len(a) != 2:
raise ValueError("TCP ports must be specified as host:port")

self.destination_addr = (a[0], int(a[1]))

self.autoreconnect = autoreconnect
Expand Down Expand Up @@ -1254,7 +1257,7 @@ def do_connect(self):
self.port.close()
self.port = None
raise e
print(e, "sleeping")
logger.info(str(e) + " sleeping")
time.sleep(1)
self.port.setblocking(0)
set_close_on_exec(self.port.fileno())
Expand All @@ -1264,12 +1267,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):
Expand Down Expand Up @@ -1307,7 +1310,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
Expand All @@ -1320,6 +1323,7 @@ def __init__(self, device, source_system=255, source_component=0, retries=3, use
a = device.split(':')
if len(a) != 2:
raise ValueError("TCP ports must be specified as host:port")

self.listen = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.listen_addr = (a[0], int(a[1]))
self.listen.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
Expand Down Expand Up @@ -1810,7 +1814,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)
Expand Down Expand Up @@ -1841,7 +1845,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:
Expand Down Expand Up @@ -2150,7 +2154,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
Expand All @@ -2163,7 +2167,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()
Expand Down Expand Up @@ -2338,7 +2342,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'''
Expand Down Expand Up @@ -2379,7 +2383,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)

Expand Down Expand Up @@ -2586,4 +2590,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)
Loading