Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
jheising authored Oct 1, 2024
2 parents 66574b4 + a9577e8 commit 4298ecc
Show file tree
Hide file tree
Showing 12 changed files with 989 additions and 262 deletions.
2 changes: 1 addition & 1 deletion MAVProxy/modules/lib/grapher.py
Original file line number Diff line number Diff line change
Expand Up @@ -601,7 +601,7 @@ def process(self, flightmode_selections, _flightmodes, block=True):
self.axes = []
self.first_only = []
re_caps = re.compile('[A-Z_][A-Z0-9_]+')
re_instance = re.compile('([A-Z_][A-Z0-9_]+)\[([0-9A-Z_]+)\]')
re_instance = re.compile(r'([A-Z_][A-Z0-9_]+)\[([0-9A-Z_]+)\]')
for f in self.fields:
caps = set(re.findall(re_caps, f))
self.msg_types = self.msg_types.union(caps)
Expand Down
24 changes: 24 additions & 0 deletions MAVProxy/modules/lib/param_help.py
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,17 @@ def get_Values_from_help(self, help):
return []

def get_bitmask_from_help(self, help):
# check for presence of "bitmask" subtree, use it by preference:
children = help.getchildren()
for c in children:
if str(c).startswith("bitmask"):
ret = {}
for entry in c.getchildren():
ret[int(entry.get('code'))] = str(entry)
return ret

# "bitmask" subtree not present, split the traditional
# "Bitmask" field ourselves:
if not hasattr(help, 'field'):
return None
field = help.field
Expand Down Expand Up @@ -165,6 +176,9 @@ def param_help(self, args):
try:
print("\n")
for f in help.field:
if f.get('name') == 'Bitmask':
# handled specially below
continue
print("%s : %s" % (f.get('name'), str(f)))
except Exception as e:
pass
Expand All @@ -177,6 +191,16 @@ def param_help(self, args):
except Exception as e:
print("Caught exception %s" % repr(e))
pass
try:
# note this is a dictionary:
values = self.get_bitmask_from_help(help)
if values is not None and len(values):
print("\nBitmask: ")
for (n, v) in values.items():
print(f"\t{int(n):3d} : {v}")
except Exception as e:
print("Caught exception %s" % repr(e))
pass
else:
print("Parameter '%s' not found in documentation" % h)

Expand Down
3 changes: 3 additions & 0 deletions MAVProxy/modules/mavproxy_battery.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,9 @@ def numcells(self, id):

def cmd_bat(self, args):
'''show battery levels'''
if 0 not in self.battery_level:
print("No battery information")
return
print("Flight battery: %u%%" % self.battery_level[0])
for id in range(9):
if self.numcells(id) != 0 and id in self.voltage_level:
Expand Down
5 changes: 3 additions & 2 deletions MAVProxy/modules/mavproxy_link.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@
'*Serial*',
'*CubePilot*',
'*Qiotek*',
'*Sierra*',
]


Expand Down Expand Up @@ -622,8 +623,8 @@ def heartbeat_is_from_autopilot(self, m):
return False

mav_autopilots_which_are_not_vehicles = frozenset([
'MAV_AUTOPILOT_INVALID',
'MAV_AUTOPILOT_RESERVED',
mavutil.mavlink.MAV_AUTOPILOT_INVALID,
mavutil.mavlink.MAV_AUTOPILOT_RESERVED,
])
if m.autopilot in mav_autopilots_which_are_not_vehicles:
return False
Expand Down
18 changes: 18 additions & 0 deletions MAVProxy/modules/mavproxy_map/mp_tile.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
import math
import threading
import os
import pathlib
import string
import time
import cv2
Expand Down Expand Up @@ -284,11 +285,28 @@ def downloader(self):
print("Downloading %s [%u left]" % (url, len(keys)))
req = url_request(url)
req.add_header('User-Agent', 'MAVProxy')

# try to re-use our cached data:
try:
mtime = os.path.getmtime(path)
req.add_header('If-Modified-Since', time.strftime('%a, %d %b %Y %H:%M:%S GMT', time.gmtime(mtime)))
except Exception:
pass

if url.find('google') != -1:
req.add_header('Referer', 'https://maps.google.com/')
resp = url_open(req)
headers = resp.info()
except url_error as e:
try:
if e.getcode() == 304:
# cache hit; touch the file to reset its refresh time
pathlib.Path(path).touch()
self._download_pending.pop(key)
continue
except Exception as ex:
pass

#print('Error loading %s' % url)
if not key in self._tile_cache:
self._tile_cache[key] = self._unavailable
Expand Down
129 changes: 102 additions & 27 deletions MAVProxy/modules/mavproxy_optitrack/DataDescriptions.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
# and receive data via a NatNet connection and decode it using the NatNetClient library.



import copy
import hashlib
import random
Expand Down Expand Up @@ -60,7 +59,7 @@ def test_hash(test_name, test_hash_str, test_object):
ret_value=False
return ret_value

def test_hash2(test_name, test_hash_str, test_object, run_test=True):
def test_hash2(test_name, test_hash_str, test_object, generator_string, run_test=True):
ret_value = K_FAIL
out_str = "FAIL"
out_str2=""
Expand All @@ -85,6 +84,8 @@ def test_hash2(test_name, test_hash_str, test_object, run_test=True):
out_str2+="%s%s test_hash_str != out_hash_str\n"%(indent_string,test_name)
out_str2+="%stest_hash_str=%s\n"%(indent_string,test_hash_str)
out_str2+="%sobj_out_hash_str=%s\n"%(indent_string,obj_out_hash_str)
out_str2+="%sUpdated Test Entry:\n"%(indent_string)
out_str2 += "%s[\"%s\", \"%s\", \"%s\", True],\n"%(indent_string,test_name,obj_out_hash_str,generator_string)
out_str2+="%sobj_out_str =\n%s"%(indent_string,obj_out_str)
ret_value = K_FAIL
print("[%s]:%s"%(out_str,test_name))
Expand Down Expand Up @@ -117,6 +118,8 @@ def get_data_sub_packet_type(new_data):
out_string="Type: 4 Device\n"
elif data_type == CameraDescription:
out_string="Type: 5 Camera\n"
elif data_type == AssetDescription:
out_string="Type: 6 Asset\n"
elif data_type == None:
out_string="Type: None\n"
else:
Expand Down Expand Up @@ -144,7 +147,7 @@ def get_as_string(self, tab_str=" ", level=0):
out_tab_str2 = get_tab_str(tab_str, level+1)
out_tab_str3 = get_tab_str(tab_str, level+2)
out_string=""
out_string+="%sMarker Set Name: %s\n"%(out_tab_str,get_as_string(self.marker_set_name))
out_string+="%sMarkerset Name: %s\n"%(out_tab_str,get_as_string(self.marker_set_name))
num_markers = len(self.marker_names_list)
out_string+="%sMarker Count : %d\n"%(out_tab_str2, num_markers)
for i in range(num_markers):
Expand All @@ -160,7 +163,7 @@ def __init__(self, marker_name="", active_label=0, pos=[0.0,0.0,0.0]):
def get_as_string(self, tab_str=" ", level=0):
out_tab_str = get_tab_str(tab_str, level)
out_string=""
out_string += "%sMarker Label: %s Position: [%f %f %f] %s\n" % \
out_string += "%sMarker Label: %s Position: [%3.2f %3.2f %3.2f] %s\n" % \
(out_tab_str, self.active_label, self.pos[0],self.pos[1],self.pos[2],self.marker_name )
return out_string

Expand All @@ -172,6 +175,7 @@ def __init__(self,sz_name="", new_id=0, parent_id=0,pos=[0.0,0.0,0.0]):
self.parent_id = parent_id
self.pos=pos
self.rb_marker_list=[]
self.rb_num = -1


def set_name(self,new_name):
Expand All @@ -198,8 +202,12 @@ def get_as_string(self, tab_str=" ", level=0):
out_tab_str = get_tab_str(tab_str, level)
out_tab_str2 = get_tab_str(tab_str, level+1)
out_string=""
out_string += "%sRigid Body :"%(out_tab_str)
if(self.rb_num > -1):
out_string += " %d\n"%(self.rb_num)
out_string += "\n"
out_string += "%sRigid Body Name : %s\n"%(out_tab_str, get_as_string(self.sz_name))
out_string += "%sID : %d\n"%(out_tab_str, self.id_num)
out_string += "%sRigid Body ID : %d\n"%(out_tab_str, self.id_num)
out_string += "%sParent ID : %d\n"%(out_tab_str, self.parent_id)
out_string += "%sPosition : [%3.2f, %3.2f, %3.2f]\n"%(out_tab_str, self.pos[0],self.pos[1],self.pos[2])
num_markers= len(self.rb_marker_list)
Expand Down Expand Up @@ -323,7 +331,7 @@ def get_as_string(self, tab_str=" ", level=0):
get_as_string(self.serial_number))
out_string += "%sWidth : %3.2f\n"%(out_tab_str, self.width)
out_string += "%sLength : %3.2f\n"%(out_tab_str, self.length)
out_string += "%sOrigin : %3.2f, %3.2f, %3.2f\n"%(out_tab_str,
out_string += "%sOrigin : [%3.2f, %3.2f, %3.2f]\n"%(out_tab_str,
self.position[0],
self.position[1],
self.position[2])
Expand Down Expand Up @@ -402,6 +410,62 @@ def get_as_string(self, tab_str="..", level=0):
self.orientation[2], self.orientation[3] )
return out_string

class MarkerDescription:
"""Marker Description class"""
def __init__(self, name, marker_id, position, marker_size, marker_params):
self.name=name
self.marker_id=marker_id
self.position=position
self.marker_size=marker_size
self.marker_params=marker_params

def get_as_string(self, tab_str="..", level=0):
"""Get Marker Description as a string"""
out_tab_str = get_tab_str(tab_str, level)
out_string = ""
out_string += "%sName : %s\n"%(out_tab_str,get_as_string(self.name))
out_string += "%sID : %d\n"%(out_tab_str,self.marker_id)
out_string += "%sPosition : [%3.2f, %3.2f, %3.2f]\n"% \
(out_tab_str,self.position[0], self.position[1], self.position[2] )
out_string += "%sSize : %3.2f\n"%(out_tab_str,self.marker_size[0])
out_string += "%sParams : %d\n"%(out_tab_str,self.marker_params)

return out_string

class AssetDescription:
"""Asset Description class"""
def __init__(self, name, assetType, assetID, rigidbodyArray, markerArray):
self.name=name
self.assetType=assetType
self.assetID=assetID
self.rigidbodyArray=rigidbodyArray
self.markerArray=markerArray

def get_as_string(self, tab_str="..", level=0):
"""Get Asset Description as a string"""
out_tab_str = get_tab_str(tab_str, level)
out_string = ""
#out_string += "Asset Description\n"
out_string += "%sName : %s\n"%(out_tab_str,get_as_string(self.name))
out_string += "%sType : %d\n"%(out_tab_str,self.assetType)
out_string += "%sID : %d\n"%(out_tab_str,self.assetID)

rbCount=0
out_string += "%sRigidBody (Bone) Count : %d\n"%(out_tab_str,len(self.rigidbodyArray))
for rigidbody in self.rigidbodyArray:
out_string += "%sRigidBody (Bone) %d:\n"%(out_tab_str,rbCount)
out_string += rigidbody.get_as_string(tab_str,level+1)
rbCount+=1

markerCount=0
out_string += "%sMarker Count : %d\n"%(out_tab_str,len(self.markerArray))
for marker in self.markerArray:
out_string += "%sMarker %d:\n"%(out_tab_str,markerCount)
out_string += marker.get_as_string(tab_str,level+1)
markerCount+=1


return out_string


# cDataDescriptions
Expand All @@ -414,6 +478,7 @@ def __init__(self):
self.marker_set_list=[]
self.rigid_body_list=[]
self.skeleton_list=[]
self.asset_list=[]
self.force_plate_list=[]
self.device_list=[]
self.camera_list=[]
Expand All @@ -425,9 +490,9 @@ def generate_order_name(self):
self.order_num += 1
return order_name

# Add Marker Set
# Add Markerset
def add_marker_set(self, new_marker_set):
"""Add a marker set"""
"""Add a Markerset"""
order_name = self.generate_order_name()

# generate order entry
Expand Down Expand Up @@ -457,6 +522,17 @@ def add_skeleton(self, new_skeleton):
self.skeleton_list.append(copy.deepcopy(new_skeleton))


# Add an asset
def add_asset(self, new_asset):
"""Add an asset"""
order_name = self.generate_order_name()

# generate order entry
pos = len(self.asset_list)
self.data_order_dict[order_name]=("asset_list", pos)
self.asset_list.append(copy.deepcopy(new_asset))


# Add a force plate
def add_force_plate(self, new_force_plate):
"""Add a force plate"""
Expand Down Expand Up @@ -502,6 +578,8 @@ def add_data(self, new_data):
self.add_device(new_data)
elif data_type == CameraDescription:
self.add_camera(new_data)
elif data_type == AssetDescription:
self.add_asset(new_data)
elif data_type is None:
data_type = None
else:
Expand All @@ -522,6 +600,10 @@ def get_object_from_list(self, list_name, pos_num):
(pos_num < len(self.skeleton_list)):
ret_value = self.skeleton_list[pos_num]

elif (list_name =="asset_list") and \
(pos_num < len(self.asset_list)):
ret_value = self.asset_list[pos_num]

elif (list_name =="force_plate_list") and \
(pos_num < len(self.force_plate_list)):
ret_value = self.force_plate_list[pos_num]
Expand All @@ -546,7 +628,7 @@ def get_as_string(self, tab_str=" ", level = 0):
out_tab_str3 = get_tab_str(tab_str,level+2)
out_string=""
num_data_sets=len(self.data_order_dict)
out_string+="%sNumber of Data Sets: %d\n"%(out_tab_str, num_data_sets)
out_string+="%sDataset Count: %d\n"%(out_tab_str, num_data_sets)
i=0
for tmp_key,tmp_value in self.data_order_dict.items():
#tmp_name,tmp_num=self.data_order_dict[data_set]
Expand All @@ -557,8 +639,8 @@ def get_as_string(self, tab_str=" ", level = 0):
tmp_string = get_data_sub_packet_type(tmp_object)
if tmp_string != "":
out_string += "%s%s"%(out_tab_str2, tmp_string)
#outputs keys for looking up objects
#out_string += "%s%s %s %d\n"%(out_tab_str2, data_set, tmp_name,tmp_num)
out_string += "%s%s %s %s\n"%(out_tab_str2,tmp_key, tmp_name,tmp_num)
if tmp_object is not None:
out_string += tmp_object.get_as_string(tab_str,level+2)
else:
Expand Down Expand Up @@ -699,27 +781,20 @@ def test_all(run_test=True):
"""Test all the Data Description classes"""
totals=[0,0,0]
if run_test is True:
test_cases=[["Test Marker Set Description 0", "754fe535286ca84bd054d9aca5e9906ab9384d92",
"generate_marker_set_description(0)",True],
["Test RB Marker 0", "0f2612abf2ce70e479d7b9912f646f12910b3310",
"generate_rb_marker(0)",True],
["Test Rigid Body Description 0", "7a4e93dcda442c1d9c5dcc5c01a247e4a6c01b66",
"generate_rigid_body_description(0)",True],
["Test Skeleton Description 0", "b4d1a031dd7c323e3d316b5312329881a6a552ca",
"generate_skeleton_description(0)",True],
["Test Force Plate Description 0", "b385dd1096bdd9f521eb48bb9cbfb3414ea075bd",
"generate_force_plate_description(0)",True],
["Test Device Description 0", "39b4fdda402bc73c0b1cd5c7f61599476aa9a926",
"generate_device_description(0)",True],
["Test Camera Description 0", "614602c5d290bda3b288138d5e25516dd1e1e85a",
"generate_camera_description(0)",True],
["Test Data Description 0", "e5f448d10087ac818a65934710a85fc7ebfdf89e",
"generate_data_descriptions(0)",True],
test_cases=[
["Test Markerset Description 0", "d918228cc347bd0dac69dd02b1a5375a4421364f", "generate_marker_set_description(0)", True],
["Test RB Marker 0", "df582ca7b764d889041b59ceb6a43251b68ca3be", "generate_rb_marker(0)", True],
["Test Rigid Body Description 0", "0ea7085657c391efe2fd349cc03f242247efbbe4", "generate_rigid_body_description(0)", True],
["Test Skeleton Description 0", "fa2a59e76f31c1d884f6554fe13e5cfcf31e703c", "generate_skeleton_description(0)", True],
["Test Force Plate Description 0", "798793a2fed302bc472b2636beff959901214be2", "generate_force_plate_description(0)", True],
["Test Device Description 0", "39b4fdda402bc73c0b1cd5c7f61599476aa9a926", "generate_device_description(0)",True],
["Test Camera Description 0", "614602c5d290bda3b288138d5e25516dd1e1e85a", "generate_camera_description(0)",True],
["Test Data Description 0", "b2fcffb251ae526e91ec9f65f5f2137f0d74db49", "generate_data_descriptions(0)", True],
]
num_tests = len(test_cases)
for i in range(num_tests):
data = eval(test_cases[i][2])
totals_tmp = test_hash2(test_cases[i][0],test_cases[i][1],data,test_cases[i][3])
totals_tmp = test_hash2(test_cases[i][0],test_cases[i][1],data,test_cases[i][2],test_cases[i][3])
totals=add_lists(totals, totals_tmp)

print("--------------------")
Expand Down
Loading

0 comments on commit 4298ecc

Please sign in to comment.