Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/master'
Browse files Browse the repository at this point in the history
  • Loading branch information
RomanBapst committed Jun 27, 2024
2 parents 3df407b + 5fc2ff8 commit f0c08d2
Show file tree
Hide file tree
Showing 3 changed files with 43 additions and 7 deletions.
7 changes: 4 additions & 3 deletions doc/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,11 @@ Files:
- **mavlink.php**: Generates online documentation from MAVLink XML - http://mavlink.org/messages/common
- **mavlink_to_html_table.xsl**: XSL transform used by **mavlink.php**
- **mavlink.css**: CSS used by online documentation
- **mavlink_gitbook.py**: Generates documentation from MAVLink XML that can be imported into gitbook
- **mavlink_to_html_table_gitbook.xsl**: XSL transform used by **mavlink_gitbook.py**
- **mavlink_xml_to_markdown.py**: Converts MAVLink XML to markdown
- **mavlink_gitbook.py** (Deprecated): Generates documentation from MAVLink XML that can be imported into gitbook - replaced by mavlink_xml_to_markdown.py
- **mavlink_to_html_table_gitbook.xsl** (Deprecated): XSL transform used by **mavlink_gitbook.py**


For more information, please visit: https://mavlink.io/en/

(c) 2009-2010 Lorenz Meier / PIXHAWK Team
(c) 2009-2023 Lorenz Meier / PIXHAWK Team
31 changes: 27 additions & 4 deletions doc/mavlink_xml_to_markdown.py
Original file line number Diff line number Diff line change
Expand Up @@ -417,6 +417,7 @@ def __init__(self, soup, parent, extension):
self.default = None
self.minValue = None
self.maxValue = None
self.multiplier = None
self.extension = extension
for attr, value in soup.attrs.items():
# We do it this way to catch all of them. New additions will throw debug
Expand All @@ -442,6 +443,8 @@ def __init__(self, soup, parent, extension):
self.minValue = value
elif attr == 'maxValue':
self.maxValue = value
elif attr == 'multiplier':
self.multiplier = value
else:
print(
f"Debug: MAVField: Unexpected attribute: {attr}, Value: {value}")
Expand Down Expand Up @@ -481,12 +484,13 @@ def __init__(self, soup, parent, extension):
parent.fieldnames.add('default')
if self.invalid:
parent.fieldnames.add('invalid')

if self.multiplier:
parent.fieldnames.add('multiplier')
# self.debug()

def debug(self):
print(
f"Debug_Field- name ({self.name}), type ({self.type}), desc({self.description}), units({self.units}), display({self.display}), instance({self.instance})")
f"Debug_Field- name ({self.name}), type ({self.type}), desc({self.description}), units({self.units}), display({self.display}), instance({self.instance}), multiplier({self.multiplier})")
# TODO - display, instance, are not output.


Expand Down Expand Up @@ -579,9 +583,13 @@ def getMarkdown(self, currentDialect):
tableHeadings.append('Type')
valueHeading = False
unitsHeading = False
multiplierHeading = False
if any(field in self.fieldnames for field in ('units',)):
unitsHeading = True
tableHeadings.append('Units')
if any(field in self.fieldnames for field in ('multiplier',)):
multiplierHeading = True
tableHeadings.append('Multiplier')
if any(field in self.fieldnames for field in ('enum', 'invalid, maxValue, minValue, default')):
valueHeading = True
tableHeadings.append('Values')
Expand All @@ -595,7 +603,8 @@ def getMarkdown(self, currentDialect):
row.append(f"`{field.type}`")
if unitsHeading:
row.append(f"{field.units if field.units else ''}")

if multiplierHeading:
row.append(f"{field.multiplier if field.multiplier else ''}")
if valueHeading:
# Values: #invalid, default, minValue, maxValue.
values = []
Expand Down Expand Up @@ -767,6 +776,7 @@ def __init__(self, soup, parent):
self.description = None
self.reserved = None
self.default = None
self.multiplier = None

for attr, value in soup.attrs.items():
# We do it this way to catch all of them. New additions will throw debug
Expand All @@ -788,6 +798,8 @@ def __init__(self, soup, parent):
self.reserved = True # TODO is it ever reserved by default, and if so make happen
elif attr == 'default':
self.default = value # TODO is it ever default by default, and if so make happen?
elif attr == 'multiplier':
self.multiplier = value
else:
print(
f"Debug: MAVCommandParam: Unexpected attribute: {attr}, Value: {value}")
Expand All @@ -813,7 +825,8 @@ def __init__(self, soup, parent):
parent.param_fieldnames.add('increment')
if self.enum:
parent.param_fieldnames.add('enum')

if self.multiplier:
parent.param_fieldnames.add('multiplier')

class MAVCommand(object):
def __init__(self, soup, basename):
Expand Down Expand Up @@ -876,12 +889,16 @@ def getMarkdown(self, currentDialect):
tableHeadings.append('Description')
valueHeading = False
unitsHeading = False
multiplierHeading = False
if any(field in self.param_fieldnames for field in ('enum', 'minValue', 'maxValue', 'increment')):
valueHeading = True
tableHeadings.append('Values')
if 'units' in self.param_fieldnames:
unitsHeading = True
tableHeadings.append('Units')
if 'multiplier' in self.param_fieldnames:
multiplierHeading = True
tableHeadings.append('Multiplier')
tableRows = []

for param in self.params:
Expand Down Expand Up @@ -910,6 +927,12 @@ def getMarkdown(self, currentDialect):
unitsString = param.units
row.append(unitsString)

if multiplierHeading:
multiplierString = " "
if param.multiplier:
multiplierString = param.multiplier
row.append(multiplierString)

tableRows.append(row)

# print("debugtablerows")
Expand Down
12 changes: 12 additions & 0 deletions message_definitions/v1.0/development.xml
Original file line number Diff line number Diff line change
Expand Up @@ -376,6 +376,18 @@
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="43004" name="MAV_CMD_EXTERNAL_WIND_ESTIMATE" hasLocation="false" isDestination="false">
<description>Set an external estimate of wind direction and speed.
This might be used to provide an initial wind estimate to the estimator (EKF) in the case where the vehicle is wind dead-reckoning, extending the time when operating without GPS before before position drift builds to an unsafe level. For this use case the command might reasonably be sent every few minutes when operating at altitude, and the value is cleared if the estimator resets itself.
</description>
<param index="1" label="Wind speed" units="m/s" minValue="0">Horizontal wind speed.</param>
<param index="2" label="Wind speed accuracy" units="m/s">Estimated 1 sigma accuracy of wind speed. Set to NaN if unknown.</param>
<param index="3" label="Direction" units="deg" minValue="0" maxValue="360">Azimuth (relative to true north) from where the wind is blowing.</param>
<param index="4" label="Direction accuracy" units="deg">Estimated 1 sigma accuracy of wind direction. Set to NaN if unknown.</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
<enum name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_FLAGS" bitmask="true">
<description>These flags indicate the sensor reporting capabilities for TARGET_ABSOLUTE.</description>
Expand Down

0 comments on commit f0c08d2

Please sign in to comment.