From 6dc55f97d430bc231692fe62b795ac4caf7d1e89 Mon Sep 17 00:00:00 2001 From: Christian Clauss Date: Thu, 19 Dec 2019 11:05:55 +0100 Subject: [PATCH] More fixes for Python 3 compatibility (#13008) * More fixes for Python 3 compatibility * Workaround if the six module is not pip installed * Lose the semicolons --- Tools/px4moduledoc/srcparser.py | 2 + Tools/setup/requirements.txt | 1 + Tools/uorb_graph/create.py | 1 - Tools/upload_log.py | 9 +- .../mavros/mavros_offboard_attctl_test.py | 1 + .../mavros/mavros_offboard_posctl_test.py | 1 + .../px4_it/mavros/mavros_test_common.py | 1 + .../python_src/px4_it/mavros/mission_test.py | 1 + msg/tools/generate_microRTPS_bridge.py | 17 +- msg/tools/uorb_rtps_classifier.py | 1 + msg/tools/uorb_to_ros_rtps_ids.py | 12 +- platforms/nuttx/Debug/Nuttx.py | 146 +++++++++--------- platforms/nuttx/NuttX/tools/oldconfig.py | 7 +- src/lib/parameters/px4params/markdownout.py | 12 +- 14 files changed, 107 insertions(+), 105 deletions(-) diff --git a/Tools/px4moduledoc/srcparser.py b/Tools/px4moduledoc/srcparser.py index 882d7fc99a..e498b33ed6 100644 --- a/Tools/px4moduledoc/srcparser.py +++ b/Tools/px4moduledoc/srcparser.py @@ -2,6 +2,8 @@ import sys import re import math import textwrap +from functools import reduce + class ModuleDocumentation(object): """ diff --git a/Tools/setup/requirements.txt b/Tools/setup/requirements.txt index 1ee025bf57..7c655be500 100644 --- a/Tools/setup/requirements.txt +++ b/Tools/setup/requirements.txt @@ -10,6 +10,7 @@ pyserial>=3.0 pyulog>=0.5.0 pyyaml setuptools>=39.2.0 +six>=1.12.0 toml>=0.9 tornado wheel>=0.31.1 diff --git a/Tools/uorb_graph/create.py b/Tools/uorb_graph/create.py index 9f73c828b0..4f35a27be9 100755 --- a/Tools/uorb_graph/create.py +++ b/Tools/uorb_graph/create.py @@ -10,7 +10,6 @@ import colorsys import json - parser = argparse.ArgumentParser( description='Generate uORB pub/sub dependency graph from source code') diff --git a/Tools/upload_log.py b/Tools/upload_log.py index ba77338b59..9bdc2e6b00 100755 --- a/Tools/upload_log.py +++ b/Tools/upload_log.py @@ -10,10 +10,10 @@ Upload an ULog file to the logs.px4.io web server. from __future__ import print_function from argparse import ArgumentParser +from six.moves import input import subprocess import sys - try: import requests except: @@ -38,12 +38,7 @@ def ask_value(text, default=None): if default != None: ask_string += ' (Press ENTER to use ' + default + ')' ask_string += ': ' - - if sys.version_info[0] < 3: - ret = raw_input(ask_string) - else: - ret = input(ask_string) - + ret = input(ask_string).strip() if ret == "" and default != None: return default return ret diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py index f35d60fe7b..952531de94 100755 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py @@ -46,6 +46,7 @@ from geometry_msgs.msg import Quaternion, Vector3 from mavros_msgs.msg import AttitudeTarget from mavros_test_common import MavrosTestCommon from pymavlink import mavutil +from six.moves import xrange from std_msgs.msg import Header from threading import Thread from tf.transformations import quaternion_from_euler diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py index 0e93198c5d..c99a649d90 100755 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py @@ -47,6 +47,7 @@ import numpy as np from geometry_msgs.msg import PoseStamped, Quaternion from mavros_test_common import MavrosTestCommon from pymavlink import mavutil +from six.moves import xrange from std_msgs.msg import Header from threading import Thread from tf.transformations import quaternion_from_euler diff --git a/integrationtests/python_src/px4_it/mavros/mavros_test_common.py b/integrationtests/python_src/px4_it/mavros/mavros_test_common.py index b9d9c9ffa7..c43ed0d305 100644 --- a/integrationtests/python_src/px4_it/mavros/mavros_test_common.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_test_common.py @@ -11,6 +11,7 @@ from mavros_msgs.srv import CommandBool, ParamGet, SetMode, WaypointClear, \ WaypointPush from pymavlink import mavutil from sensor_msgs.msg import NavSatFix +from six.moves import xrange class MavrosTestCommon(unittest.TestCase): diff --git a/integrationtests/python_src/px4_it/mavros/mission_test.py b/integrationtests/python_src/px4_it/mavros/mission_test.py index 93432d8b86..6b34bab029 100755 --- a/integrationtests/python_src/px4_it/mavros/mission_test.py +++ b/integrationtests/python_src/px4_it/mavros/mission_test.py @@ -53,6 +53,7 @@ from mavros import mavlink from mavros_msgs.msg import Mavlink, Waypoint, WaypointReached from mavros_test_common import MavrosTestCommon from pymavlink import mavutil +from six.moves import xrange from threading import Thread diff --git a/msg/tools/generate_microRTPS_bridge.py b/msg/tools/generate_microRTPS_bridge.py index fc076fb3c1..e336bda753 100644 --- a/msg/tools/generate_microRTPS_bridge.py +++ b/msg/tools/generate_microRTPS_bridge.py @@ -53,6 +53,13 @@ try: except ImportError: raise ImportError( "Failed to import yaml. You may need to install it with 'sudo pip install pyyaml'") +try: + from six.moves import input +except ImportError: + try: + input = raw_input # Python 2 + except NameError: + pass # Python 3 def check_rtps_id_uniqueness(classifier): @@ -281,9 +288,9 @@ if agent == False and client == False: if del_tree: if agent: - _continue = str(raw_input("\nFiles in " + agent_out_dir + - " will be erased, continue?[Y/n]\n")) - if _continue == "N" or _continue == "n": + _continue = str(input("\nFiles in " + agent_out_dir + + " will be erased, continue?[Y/n]\n")) + if _continue.strip() in ("N", "n"): print("Aborting execution...") exit(-1) else: @@ -291,9 +298,9 @@ if del_tree: shutil.rmtree(agent_out_dir) if client: - _continue = str(raw_input( + _continue = str(input( "\nFiles in " + client_out_dir + " will be erased, continue?[Y/n]\n")) - if _continue == "N" or _continue == "n": + if _continue.strip() in ("N", "n"): print("Aborting execution...") exit(-1) else: diff --git a/msg/tools/uorb_rtps_classifier.py b/msg/tools/uorb_rtps_classifier.py index 15f02da410..c9f5f51ab6 100644 --- a/msg/tools/uorb_rtps_classifier.py +++ b/msg/tools/uorb_rtps_classifier.py @@ -35,6 +35,7 @@ import sys import os import argparse +import errno import yaml import re import difflib diff --git a/msg/tools/uorb_to_ros_rtps_ids.py b/msg/tools/uorb_to_ros_rtps_ids.py index 6608e86f98..cf9749c3f3 100644 --- a/msg/tools/uorb_to_ros_rtps_ids.py +++ b/msg/tools/uorb_to_ros_rtps_ids.py @@ -3,10 +3,12 @@ Script to read an yaml file containing the RTPS message IDs and update the naming convention to PascalCase """ +import errno import os import yaml import sys import argparse +import six __author__ = 'PX4 Development Team' __copyright__ = \ @@ -91,14 +93,8 @@ def update_dict(list): if verbose: num_of_msgs = 0 for i, dictionary in enumerate(list["rtps"]): - # implementation depends on the Python version being used - if sys.version_info[0] < 3: - dict = {k: v.title().replace('_', '') if isinstance( - v, basestring) else v for k, v in dictionary.iteritems()} - else: - dict = {k: v.title().replace('_', '') if isinstance( - v, str) else v for k, v in dictionary.items()} - list["rtps"][i] = dict + list["rtps"][i] = {k: v.title().replace('_', '') if isinstance( + v, six.string_types) else v for k, v in six.iteritems(dictionary)} if verbose: num_of_msgs += 1 if verbose: diff --git a/platforms/nuttx/Debug/Nuttx.py b/platforms/nuttx/Debug/Nuttx.py index 776cc90349..71d898566a 100644 --- a/platforms/nuttx/Debug/Nuttx.py +++ b/platforms/nuttx/Debug/Nuttx.py @@ -211,7 +211,7 @@ class NX_task(object): def waiting_for(self): """return a description of what the task is waiting for, if it is waiting""" if self._state_is('TSTATE_WAIT_SEM'): - try: + try: waitsem = self._tcb['waitsem'].dereference() waitsem_holder = waitsem['holder'] holder = NX_task.for_tcb(waitsem_holder['htcb']) @@ -234,8 +234,8 @@ class NX_task(object): @property def is_runnable(self): """tests whether the task is runnable""" - if (self._state_is('TSTATE_TASK_PENDING') or - self._state_is('TSTATE_TASK_READYTORUN') or + if (self._state_is('TSTATE_TASK_PENDING') or + self._state_is('TSTATE_TASK_READYTORUN') or self._state_is('TSTATE_TASK_RUNNING')): return True return False @@ -271,7 +271,7 @@ class NX_task(object): def __str__(self): return "{}:{}".format(self.pid, self.name) - + def showoff(self): print("-------") print(self.pid,end = ", ") @@ -282,7 +282,7 @@ class NX_task(object): print(self._tcb['adj_stack_size'],end = ", ") print(self.file_descriptors) print(self.registers) - + def __format__(self, format_spec): return format_spec.format( pid = self.pid, @@ -294,7 +294,7 @@ class NX_task(object): file_descriptors = self.file_descriptors, registers = self.registers ) - + class NX_show_task (gdb.Command): """(NuttX) prints information about a task""" @@ -391,7 +391,7 @@ class NX_show_interrupted_thread (gdb.Command): def invoke(self, args, from_tty): regs = gdb.lookup_global_symbol('current_regs').value() - if regs is 0: + if regs == 0: raise gdb.GdbError('not in interrupt context') else: registers = NX_register_set.with_xcpt_regs(regs) @@ -409,7 +409,7 @@ class NX_check_tcb(gdb.Command): """ check the tcb of a task from a address """ def __init__(self): super(NX_check_tcb,self).__init__('show tcb', gdb.COMMAND_USER) - + def invoke(self,args,sth): tasks = NX_task.tasks() print("tcb int: ",int(args)) @@ -425,29 +425,29 @@ NX_check_tcb() class NX_tcb(object): def __init__(self): pass - + def is_in(self,arg,list): for i in list: if arg == i: - return True; + return True return False - + def find_tcb_list(self,dq_entry_t): tcb_list = [] tcb_ptr = dq_entry_t.cast(gdb.lookup_type('struct tcb_s').pointer()) first_tcb = tcb_ptr.dereference() - tcb_list.append(first_tcb); + tcb_list.append(first_tcb) next_tcb = first_tcb['flink'].dereference() while not self.is_in(parse_int(next_tcb['pid']),[parse_int(t['pid']) for t in tcb_list]): - tcb_list.append(next_tcb); - old_tcb = next_tcb; + tcb_list.append(next_tcb) + old_tcb = next_tcb next_tcb = old_tcb['flink'].dereference() - + return [t for t in tcb_list if parse_int(t['pid'])<2000] - + def getTCB(self): list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] - tcb_list = []; + tcb_list = [] for l in list_of_listsnames: li = gdb.lookup_global_symbol(l) print(li) @@ -456,49 +456,49 @@ class NX_tcb(object): class NX_check_stack_order(gdb.Command): """ Check the Stack order corresponding to the tasks """ - + def __init__(self): super(NX_check_stack_order,self).__init__('show check_stack', gdb.COMMAND_USER) - + def is_in(self,arg,list): for i in list: if arg == i: - return True; + return True return False - + def find_tcb_list(self,dq_entry_t): tcb_list = [] tcb_ptr = dq_entry_t.cast(gdb.lookup_type('struct tcb_s').pointer()) first_tcb = tcb_ptr.dereference() - tcb_list.append(first_tcb); + tcb_list.append(first_tcb) next_tcb = first_tcb['flink'].dereference() while not self.is_in(parse_int(next_tcb['pid']),[parse_int(t['pid']) for t in tcb_list]): - tcb_list.append(next_tcb); - old_tcb = next_tcb; + tcb_list.append(next_tcb) + old_tcb = next_tcb next_tcb = old_tcb['flink'].dereference() - + return [t for t in tcb_list if parse_int(t['pid'])<2000] - + def getTCB(self): list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] - tcb_list = []; + tcb_list = [] for l in list_of_listsnames: li = gdb.lookup_global_symbol(l) cursor = li.value()['head'] tcb_list = tcb_list + self.find_tcb_list(cursor) return tcb_list - + def getSPfromTask(self,tcb): regmap = NX_register_set.v7em_regmap a =tcb['xcp']['regs'] return parse_int(a[regmap['SP']]) - + def find_closest(self,list,val): tmp_list = [abs(i-val) for i in list] tmp_min = min(tmp_list) idx = tmp_list.index(tmp_min) return idx,list[idx] - + def find_next_stack(self,address,_dict_in): add_list = [] name_list = [] @@ -510,28 +510,28 @@ class NX_check_stack_order(gdb.Command): name_list.append(self.check_name(key)+"_SP") else: name_list.append(self.check_name(key)) - + idx,new_address = self.find_closest(add_list,address) return new_address,name_list[idx] - + def check_name(self,name): if isinstance(name,(list)): - name = name[0]; + name = name[0] idx = name.find("\\") newname = name[:idx] - + return newname - + def invoke(self,args,sth): - tcb = self.getTCB(); - stackadresses={}; + tcb = self.getTCB() + stackadresses={} for t in tcb: - p = []; + p = [] #print(t.name,t._tcb['stack_alloc_ptr']) p.append(parse_int(t['stack_alloc_ptr'])) p.append(parse_int(t['adj_stack_ptr'])) p.append(self.getSPfromTask(t)) - stackadresses[str(t['name'])] = p; + stackadresses[str(t['name'])] = p address = int("0x30000000",0) print("stack address : process") for i in range(len(stackadresses)*3): @@ -539,12 +539,12 @@ class NX_check_stack_order(gdb.Command): print(hex(address),": ",name) NX_check_stack_order() - + class NX_run_debug_util(gdb.Command): """ show the registers of a task corresponding to a tcb address""" def __init__(self): super(NX_run_debug_util,self).__init__('show regs', gdb.COMMAND_USER) - + def printRegisters(self,task): regmap = NX_register_set.v7em_regmap a =task._tcb['xcp']['regs'] @@ -553,14 +553,14 @@ class NX_run_debug_util(gdb.Command): hex_addr= hex(int(a[regmap[reg]])) eval_string = 'info line *'+str(hex_addr) print(reg,": ",hex_addr,) - + def getPCfromTask(self,task): regmap = NX_register_set.v7em_regmap a =task._tcb['xcp']['regs'] return hex(int(a[regmap['PC']])) - + def invoke(self,args,sth): - tasks = NX_task.tasks() + tasks = NX_task.tasks() if args == '': for t in tasks: self.printRegisters(t) @@ -568,56 +568,56 @@ class NX_run_debug_util(gdb.Command): print("this is the location in code where the current threads $pc is:") gdb.execute(eval_str) else: - tcb_nr = int(args); + tcb_nr = int(args) print("tcb_nr = ",tcb_nr) t = tasks[tcb_nr] self.printRegisters(t) eval_str = "list *"+str(self.getPCfromTask(t)) print("this is the location in code where the current threads $pc is:") gdb.execute(eval_str) - + NX_run_debug_util() - + class NX_search_tcb(gdb.Command): """ shot PID's of all running tasks """ - + def __init__(self): super(NX_search_tcb,self).__init__('show alltcb', gdb.COMMAND_USER) - + def is_in(self,arg,list): for i in list: if arg == i: - return True; + return True return False - + def find_tcb_list(self,dq_entry_t): tcb_list = [] tcb_ptr = dq_entry_t.cast(gdb.lookup_type('struct tcb_s').pointer()) first_tcb = tcb_ptr.dereference() - tcb_list.append(first_tcb); + tcb_list.append(first_tcb) next_tcb = first_tcb['flink'].dereference() while not self.is_in(parse_int(next_tcb['pid']),[parse_int(t['pid']) for t in tcb_list]): - tcb_list.append(next_tcb); - old_tcb = next_tcb; + tcb_list.append(next_tcb) + old_tcb = next_tcb next_tcb = old_tcb['flink'].dereference() - + return [t for t in tcb_list if parse_int(t['pid'])<2000] - + def invoke(self,args,sth): list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] - tasks = []; + tasks = [] for l in list_of_listsnames: li = gdb.lookup_global_symbol(l) cursor = li.value()['head'] tasks = tasks + self.find_tcb_list(cursor) - + # filter for tasks that are listed twice tasks_filt = {} for t in tasks: - pid = parse_int(t['pid']); + pid = parse_int(t['pid']) if not pid in tasks_filt.keys(): - tasks_filt[pid] = t['name']; + tasks_filt[pid] = t['name'] print('{num_t} Tasks found:'.format(num_t = len(tasks_filt))) for pid in tasks_filt.keys(): print("PID: ",pid," ",tasks_filt[pid]) @@ -626,36 +626,36 @@ NX_search_tcb() class NX_my_bt(gdb.Command): - """ 'fake' backtrace: backtrace the stack of a process and check every suspicious address for the list + """ 'fake' backtrace: backtrace the stack of a process and check every suspicious address for the list arg: tcb_address$ (can easily be found by typing 'showtask'). """ - + def __init__(self): super(NX_my_bt,self).__init__('show mybt', gdb.COMMAND_USER) - + def readmem(self,addr): ''' read memory at addr and return nr - ''' + ''' str_to_eval = "x/x "+hex(addr) resp = gdb.execute(str_to_eval,to_string = True) idx = resp.find('\t') return int(resp[idx:],16) - + def is_in_bounds(self,val): lower_bound = int("08004000",16) - upper_bound = int("080ae0c0",16); + upper_bound = int("080ae0c0",16) #print(lower_bound," ",val," ",upper_bound) if val>lower_bound and val