Merge branch 'main' into dev/dshot_stuff2

This commit is contained in:
Jacob Dahl 2026-02-10 12:29:38 -09:00
commit 4cfda1feed
221 changed files with 8634 additions and 1017 deletions

View File

@ -90,6 +90,9 @@ jobs:
mkdir -p /opt/px4_ws/src
cd /opt/px4_ws/src
git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib.git
# Ignore python packages due to compilation issue (can be enabled when updating ROS)
touch px4-ros2-interface-lib/px4_ros2_py/COLCON_IGNORE || true
touch px4-ros2-interface-lib/examples/python/COLCON_IGNORE || true
cd ..
# Copy messages to ROS workspace
"${PX4_DIR}/Tools/copy_to_ros_ws.sh" "$(pwd)"

View File

@ -101,6 +101,6 @@ param set-default NAV_ACC_RAD 5
param set-default NAV_DLL_ACT 2
param set-default VT_FWD_THRUST_EN 4
param set-default VT_F_TRANS_THR 0.3
param set-default VT_F_TRANS_THR 1
param set-default VT_TYPE 2
param set-default FD_ESCS_EN 0

View File

@ -8,6 +8,803 @@ Also generates docs/en/middleware/dds_topics.md from dds_topics.yaml
import os
import argparse
import sys
import re
VALID_FIELDS = { #Note, also have to add the message types as those can be fields
'uint64',
'uint16',
'uint8',
'uint32'
}
ALLOWED_UNITS = set(["m", "m/s", "m/s^2", "(m/s)^2", "deg", "deg/s", "rad", "rad/s", "rad^2", "rpm" ,"V", "A", "mA", "mAh", "W", "dBm", "h", "s", "ms", "us", "Ohm", "MB", "Kb/s", "degC","Pa","%","-"])
invalid_units = set()
ALLOWED_FRAMES = set(["NED","Body"])
ALLOWED_INVALID_VALUES = set(["NaN", "0"])
ALLOWED_CONSTANTS_NOT_IN_ENUM = set(["ORB_QUEUE_LENGTH","MESSAGE_VERSION"])
class Error:
def __init__(self, type, message, linenumber=None, issueString = None, field = None):
self.type = type
self.message = message
self.linenumber = linenumber
self.issueString = issueString
self.field = field
def display_error(self):
#print(f"Debug: Error: display_error")
if 'trailing_whitespace' == self.type:
if self.issueString.strip():
print(f"NOTE: Line has trailing whitespace ({self.message}: {self.linenumber}): {self.issueString}")
else:
print(f"NOTE: Line has trailing whitespace ({self.message}: {self.linenumber})")
elif 'leading_whitespace_field_or_constant' == self.type:
print(f"NOTE: Whitespace before field or constant ({self.message}: {self.linenumber}): {self.issueString}")
elif 'field_or_constant_has_multiple_whitepsace' == self.type:
print(f"NOTE: Field/constant has more than one sequential whitespace character ({self.message}: {self.linenumber}): {self.issueString}")
elif 'empty_start_line' == self.type:
print(f"NOTE: Empty line at start of file ({self.message}: {self.linenumber})")
elif 'internal_comment' == self.type:
print(f"NOTE: Internal Comment ({self.message}: {self.linenumber})\n {self.issueString}")
elif 'internal_comment_empty' == self.type:
print(f"NOTE: Empty Internal Comment ({self.message}: {self.linenumber})")
elif 'summary_missing' == self.type:
print(f"WARNING: No message description ({self.message})")
elif 'topic_error' == self.type:
print(f"NOTE: TOPIC ISSUE: {self.issueString}")
elif 'unknown_unit' == self.type:
print(f"WARNING: Unknown Unit: [{self.issueString}] on `{self.field}` ({self.message}: {self.linenumber})")
elif 'constant_not_in_assigned_enum' == self.type:
print(f"WARNING: `{self.issueString}` constant: Prefix not in `@enum` field metadata ({self.message}: {self.linenumber})")
elif 'unknown_invalid_value' == self.type:
print(f"WARNING: Unknown @invalid value: [{self.issueString}] on `{self.field}` ({self.message}: {self.linenumber})")
elif 'unknown_frame' == self.type:
print(f"WARNING: Unknown @frame: [{self.issueString}] on `{self.field}` ({self.message}: {self.linenumber})")
elif 'command_no_params_pipes' == self.type:
print(f"WARNING: `{self.field}` command has no parameters (pipes): [{self.issueString}] ({self.message}: {self.linenumber})")
elif 'command_missing_params' == self.type:
print(f"WARNING: `{self.field}` command missing params - should be 7 params surrounded by 8 pipes: [{self.issueString}] ({self.message}: {self.linenumber})")
elif 'command_too_many_params' == self.type:
print(f"WARNING: `{self.field}` command too many params (should be 7). Extras: [{self.issueString}] ({self.message}: {self.linenumber})")
else:
self.display_info()
def display_info(self):
"""
Display info about an error.
Used as a fallback if error does not have specific printout in display_error()
"""
#print(f"Debug: Error: display_info")
print(f" type: {self.type}, message: {self.message}, linenumber: {self.linenumber}, issueString: {self.issueString}, field: {self.field}")
class Enum:
def __init__(self, name, parentMessage):
self.name = name
self.parent = parentMessage
self.enumValues = dict()
def display_info(self):
"""
Display info about an enum
"""
print(f"Debug: Enum: display_info")
print(f" name: {self.name}")
for key, value in self.enumValues.items():
value.display_info()
class ConstantValue:
def __init__(self, name, type, value, comment, line_number):
self.name = name.strip()
self.type = type.strip()
self.value = value.strip()
self.comment = comment
self.line_number = line_number
if not self.value:
print(f"Debug WARNING: NO VALUE in ConstantValue: {self.name}") ## TODO make into ERROR
exit()
# TODO if value or name are empty, error
def display_info(self):
print(f"Debug: ConstantValue: display_info")
print(f" name: {self.name}, type: {self.type}, value: {self.value}, comment: {self.comment}, line: {self.line_number}")
class CommandParam:
"""
Represents an individual param in a command constant
Encapsulates parsing of the param to extract units etc.
"""
def __init__(self, num, paramText, line_number, parentCommand):
self.paramNum = num
self.paramText = paramText.strip()
self.enum = None
self.range = None
#self.type = type
self.units = []
self.enums = []
self.minValue = None
self.maxValue = None
self.invalidValue = None
self.frameValue = None
self.lineNumber = line_number
self.parent = parentCommand
self.parentMessage = self.parent.parent
match = None
if self.paramText:
match = re.match(r'^((?:\[[^\]]*\]\s*)+)(.*)$', paramText)
self.description = paramText
bracketed_part = None
if match:
bracketed_part = match.group(1).strip() # .strip() removes trailing whitespace from the bracketed part
self.description = match.group(2).strip()
if bracketed_part:
# get units
bracket_content_matches = re.findall(r'\[(.*?)\]', bracketed_part)
#print(f"DEBUG: bracket_content_matches: {bracket_content_matches}")
for item in bracket_content_matches:
item = item.strip()
if item.startswith('@'): # Not a unit:
if item.startswith('@enum'):
item = item.split(" ")
enum = item[1].strip()
if enum and enum not in self.enums:
self.enums.append(enum)
# Create parent enum objects for any enums created in this step
for enumName in self.enums:
if not enumName in self.parentMessage.enums:
self.parentMessage.enums[enumName]=Enum(enumName,self.parentMessage)
elif item.startswith('@range'):
item = item[6:].strip().split(",")
self.range = item
self.minValue = item[0].strip()
self.maxValue = item[1].strip()
elif item.startswith('@invalid'):
self.invalidValue = item[8:].strip()
#TODO: Do we require a description? (not currently)
if self.invalidValue.split(" ")[0] not in ALLOWED_INVALID_VALUES:
print(f"TODO: Command param do not support @invalid: {self.invalidValue}")
"""
error = Error("unknown_invalid_value", self.parent.filename, self.lineNumber, self.invalidValue, self.name)
#error.display_error()
if not "unknown_invalid_value" in self.parent.errors:
self.parent.errors["unknown_invalid_value"] = []
self.parent.errors["unknown_invalid_value"].append(error)
"""
elif item.startswith('@frame'):
self.frameValue = item[6:].strip()
print(f"TODO: Command param do not support @frame: {self.frameValue}")
"""
if self.frameValue not in ALLOWED_FRAMES:
error = Error("unknown_frame", self.parent.filename, self.lineNumber, self.frameValue, self.name)
#error.display_error()
if not "unknown_frame" in self.parent.errors:
self.parent.errors["unknown_frame"] = []
self.parent.errors["unknown_frame"].append(error)
"""
else:
print(f"WARNING: Unhandled metadata in message comment: {item}")
# TODO - report errors for different kinds of metadata
exit()
else: # bracket is a unit
unit = item.strip()
if item == "-":
unit = ""
if unit and unit not in self.units:
self.units.append(unit)
if unit not in ALLOWED_UNITS:
invalid_units.add(unit)
error = Error("unknown_unit", self.parentMessage.filename, self.lineNumber, unit, self.parent.name)
#error.display_error()
if not "unknown_unit" in self.parentMessage.errors:
self.parentMessage.errors["unknown_unit"] = []
self.parentMessage.errors["unknown_unit"].append(error)
def display_info(self):
print(f"Debug: CommandParam: display_info")
print(f" id: {self.paramNum}")
print(f" paramText: {self.paramText}\n unit: {self.units}\n enums: {self.enums}\n lineNumber: {self.lineNumber}\n range: {self.range}\n minValue: {self.minValue}\n maxValue: {self.maxValue}\n invalidValue: {self.invalidValue}\n frameValue: {self.frameValue}\n parent: {self.parent}\n ")
class CommandConstant:
"""
Represents a constant that is a command definition.
Encapsulates parsing of the command format.
The individual params are further parsed in CommandParam
"""
def __init__(self, name, type, value, comment, line_number, parentMessage):
self.name = name.strip()
self.type = type.strip()
self.value = value.strip()
self.comment = comment
self.line_number = line_number
self.parent = parentMessage
self.description = self.comment
self.param1 = None
self.param2 = None
self.param3 = None
self.param4 = None
self.param5 = None
self.param6 = None
self.param7 = None
if not self.value:
print(f"Debug WARNING: NO VALUE in CommandConstant: {self.name}") ## TODO make into ERROR
exit()
if not self.comment: # This is an bug for a command
#print(f"Debug WARNING: NO COMMENT in CommandConstant: {self.name}") ## TODO make into ERROR
return
# Parse command comment to get the description and parameters.
# print(f"Debug CommandConstant: {self.comment}")
if not "|" in self.comment:
# This is an error for a command constant
error = Error("command_no_params_pipes", self.parent.filename, self.line_number, self.comment, self.name)
#error.display_error()
if not "command_no_params_pipes" in self.parent.errors:
self.parent.errors["command_no_params_pipes"] = []
self.parent.errors["command_no_params_pipes"].append(error)
return
# Split on pipes
commandSplit = self.comment.split("|")
if len(commandSplit) < 9:
# Should 7 pipes, so each command is fully surrounded
error = Error("command_missing_params", self.parent.filename, self.line_number, self.comment, self.name)
#error.display_error()
if not "command_missing_params" in self.parent.errors:
self.parent.errors["command_missing_params"] = []
self.parent.errors["command_missing_params"].append(error)
self.description = commandSplit[0].strip()
self.description = self.description if self.description else None
params_to_update = commandSplit[1:8]
for i, value in enumerate(params_to_update, start=1):
if value.strip():
# parse the param
param = CommandParam(i, value, self.line_number, self)
#param.display_info() # DEBUG CODE XXX
setattr(self, f"param{i}", param)
# parse the param
if len(commandSplit) > 8:
extras = commandSplit[8:]
error = Error("command_too_many_params", self.parent.filename, self.line_number, extras, self.name)
if not "command_too_many_params" in self.parent.errors:
self.parent.errors["command_too_many_params"] = []
self.parent.errors["command_too_many_params"].append(error)
# TODO if value or name are empty, error
def markdown_out(self):
#print("DEBUG: CommandConstant.markdown_out")
output = f"""### {self.name} ({self.value})
{self.description}
Param | Units | Range/Enum | Description
--- | --- | --- | ---
"""
for i in range(1, 8):
attr_name = f"param{i}"
# getattr returns None if the attribute doesn't exist
val = getattr(self, attr_name, None)
if val is not None:
rangeVal = ""
if val.minValue or val.maxValue:
rangeVal = f"[{val.minValue if val.minValue else '-'} : {val.maxValue if val.maxValue else '-' }]"
output+=f"{i} | {", ".join(val.units)}|{', '.join(f"[{e}](#{e})" for e in val.enums)}{rangeVal} | {val.description}\n"
else:
output+=f"{i} | | | ?\n"
output+=f"\n"
return output
def display_info(self):
print(f"Debug: CommandConstant: display_info")
print(f" name: {self.name}, type: {self.type}, value: {self.value}, comment: {self.comment}, line: {self.line_number}")
print(f" description: {self.description}\n param1: {self.param1}\n param2: {self.param2}\n param3: {self.param3}\n param4: {self.param4}\n param5: {self.param5}\n param6: {self.param6}\n param7: {self.param7}")
class MessageField:
"""
Represents a field.
Encapsulates parsing of the field information.
"""
def __init__(self, name, type, comment, line_number, parentMessage):
self.name = name
self.type = type
self.comment = comment
self.unit = None
self.enums = None
self.minValue = None
self.maxValue = None
self.invalidValue = None
self.frameValue = None
self.lineNumber = line_number
self.parent = parentMessage
#print(f"MessageComment: {comment}")
match = None
if self.comment:
match = re.match(r'^((?:\[[^\]]*\]\s*)+)(.*)$', comment)
self.description = comment
bracketed_part = None
if match:
bracketed_part = match.group(1).strip() # .strip() removes trailing whitespace from the bracketed part
self.description = match.group(2).strip()
if bracketed_part:
# get units
bracket_content_matches = re.findall(r'\[(.*?)\]', bracketed_part)
#print(f"bracket_content_matches: {bracket_content_matches}")
for item in bracket_content_matches:
item = item.strip()
if item.startswith('@'): # Not a unit:
if item.startswith('@enum'):
item = item.split(" ")
self.enums = item[1:]
# Create parent enum objects
for enumName in self.enums:
if not enumName in parentMessage.enums:
parentMessage.enums[enumName]=Enum(enumName,parentMessage)
elif item.startswith('@range'):
item = item[6:].strip().split(",")
self.minValue = item[0].strip()
self.maxValue = item[1].strip()
elif item.startswith('@invalid'):
self.invalidValue = item[8:].strip()
#TODO: Do we require a description? (not currently)
if self.invalidValue.split(" ")[0] not in ALLOWED_INVALID_VALUES:
error = Error("unknown_invalid_value", self.parent.filename, self.lineNumber, self.invalidValue, self.name)
#error.display_error()
if not "unknown_invalid_value" in self.parent.errors:
self.parent.errors["unknown_invalid_value"] = []
self.parent.errors["unknown_invalid_value"].append(error)
elif item.startswith('@frame'):
self.frameValue = item[6:].strip()
if self.frameValue not in ALLOWED_FRAMES:
error = Error("unknown_frame", self.parent.filename, self.lineNumber, self.frameValue, self.name)
#error.display_error()
if not "unknown_frame" in self.parent.errors:
self.parent.errors["unknown_frame"] = []
self.parent.errors["unknown_frame"].append(error)
else:
print(f"WARNING: Unhandled metadata in message comment: {item}")
# TODO - report errors for different kinds of metadata
exit()
else: # bracket is a unit
self.unit = item
if self.unit not in ALLOWED_UNITS:
invalid_units.add(self.unit)
error = Error("unknown_unit", self.parent.filename, self.lineNumber, self.unit, self.name)
#error.display_error()
if not "unknown_unit" in self.parent.errors:
self.parent.errors["unknown_unit"] = []
self.parent.errors["unknown_unit"].append(error)
if item == "-":
self.unit = ""
def display_info(self):
print(f"Debug: MessageField: display_info")
print(f" name: {self.name}, type: {self.type}, description: {self.description}, enums: {self.enums}, minValue: {self.minValue}, maxValue: {self.maxValue}, invalidValue: {self.invalidValue}, frameValue: {self.frameValue}")
class UORBMessage:
"""
Represents a whole message, including fields, enums, commands, constants.
The parser function delegates the parsing of each part of the message to
more appropriate classes, once the specific type of line has been identified.
"""
def __init__(self, filename):
self.filename = filename
msg_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../../msg")
self.msg_filename = os.path.join(msg_path, self.filename)
self.name = os.path.splitext(os.path.basename(msg_file))[0]
self.shortDescription = ""
self.longDescription = ""
self.fields = []
self.constantFields = dict()
self.commandConstants = dict()
self.enums = dict()
self.output_file = os.path.join(output_dir, f"{self.name}.md")
self.topics = []
self.errors = dict()
self.parseFile()
if args.errors:
#print(f"DEBUG: args.errors: {args.errors}")
if args.error_messages:
messages = args.error_messages.split(" ")
#print(f"DEBUG: args.errors: {messages},self.name: {self.name}")
if self.name in messages:
self.reportErrors()
#print(f"Debug: {self.name} in {messages}")
else:
self.reportErrors()
def reportErrors(self):
#print(f"Debug: UORBMessage: reportErrors()")
for errorType, errors in self.errors.items():
for error in errors:
error.display_error()
def markdown_out(self):
#print(f"Debug: UORBMessage: markdown_out()")
# Add page header (forces wide pages)
markdown = f"""---
pageClass: is-wide-page
---
# {self.name} (UORB message)
"""
## Append description info if present
markdown += f"{self.shortDescription}\n\n" if self.shortDescription else ""
markdown += f"{self.longDescription}\n\n" if self.longDescription else ""
topicList = " ".join(self.topics)
markdown += f"**TOPICS:** {topicList}\n\n"
# Generate field docs
markdown += f"## Fields\n\n"
markdown += "Name | Type | Unit [Frame] | Range/Enum | Description\n"
markdown += "--- | --- | --- | --- | ---\n"
for field in self.fields:
unit = f"{field.unit}" if field.unit else ""
frame = f"[{field.frameValue}]" if field.frameValue else ""
unit = f"{unit} {frame}"
unit.strip()
unit = f" {unit}"
value = " "
if field.enums:
value = ""
for enum in field.enums:
value += f"[{enum}](#{enum})"
value = value.strip()
value = f"{value}"
elif field.minValue or field.maxValue:
value = f"[{field.minValue if field.minValue else '-'} : {field.maxValue if field.maxValue else '-' }]"
description = f" {field.description}" if field.description else ""
invalid = f" (Invalid: {field.invalidValue}) " if field.invalidValue else ""
markdown += f"{field.name} | `{field.type}` |{unit}|{value}|{description}{invalid}\n"
# Generate table for command docs
if len(self.commandConstants) > 0:
#print("DEBUGCOMMAND")
markdown += f"\n## Commands\n\n"
"""
markdown += "Name | Type | Value | Description\n"
markdown += "--- | --- | --- |---\n"
for name, command in self.commandConstants.items():
description = f" {command.comment} " if enum.comment else " "
markdown += f'<a href="#{name}"></a> {name} | `{command.type}` | {command.value} |{description}\n'
"""
for commandConstant in self.commandConstants.values():
#print(commandConstant)
markdown += commandConstant.markdown_out()
# Generate enum docs
if len(self.enums) > 0:
markdown += f"\n## Enums\n"
for name, enum in self.enums.items():
markdown += f"\n### {name} {{#{name}}}\n\n"
markdown += "Name | Type | Value | Description\n"
markdown += "--- | --- | --- | ---\n"
for enumValueName, enumValue in enum.enumValues.items():
description = f" {enumValue.comment} " if enumValue.comment else " "
markdown += f'<a href="#{enumValueName}"></a> {enumValueName} | `{enumValue.type}` | {enumValue.value} |{description}\n'
# Generate table for constants docs
if len(self.constantFields) > 0:
markdown += f"\n## Constants\n\n"
markdown += "Name | Type | Value | Description\n"
markdown += "--- | --- | --- |---\n"
for name, enum in self.constantFields.items():
description = f" {enum.comment} " if enum.comment else " "
markdown += f'<a href="#{name}"></a> {name} | `{enum.type}` | {enum.value} |{description}\n'
# Append msg contents to the end
with open(self.msg_filename, 'r') as source_file:
msg_contents = source_file.read()
msg_contents = msg_contents.strip()
#Format markdown using msg name, comment, url, contents.
markdown += f"""
## Source Message
[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/{self.filename})
::: details Click here to see original file
```c
{msg_contents}
```
:::
"""
with open(self.output_file, 'w') as content_file:
content_file.write(markdown)
#exit()
def display_info(self):
print(f"UORBMessage: display_info")
print(f" name: {self.name}")
print(f" filename: {self.filename}, ")
print(f" msg_filename: {self.msg_filename}, ")
print(f"self.shortDescription: {self.shortDescription}")
print(f"self.longDescription: {self.longDescription}")
print(f"self.enums: {self.enums}")
for enum, enumObject in self.enums.items():
enumObject.display_info()
# Output our data so far
for field in self.fields:
field.display_info()
for enumvalue in self.constantFields:
print(enumvalue)
self.constantFields[enumvalue].display_info()
def handleField(self, line, line_number, parentMessage):
#print(f"debug: handleField: (line): \n {line}")
# Note, here we know we don't have a comment or a topic.
# We expect it to be a field.
# Check field doesn't have leading whitespace (trailing spaces already checked)
if line[:1].isspace(): # Returns True for ' ', '\t', '\n', '\r', etc.
#print("First character is whitespace")
error = Error("leading_whitespace_field_or_constant", self.filename, line_number, line)
if not "leading_whitespace_field_or_constant" in self.errors:
self.errors["leading_whitespace_field_or_constant"] = []
self.errors["leading_whitespace_field_or_constant"].append(error)
# Now we can parse the stripped line
fieldOrConstant = line.strip()
# Check that the field or constant has only single whitespace separators
stripped_fieldOrConstant = re.sub(r'\s+', ' ', fieldOrConstant) # Collapse all spaces to a single space (LHS already stripped).
if stripped_fieldOrConstant != fieldOrConstant:
#print("Field/Constant has multiple whitespace characters") # Since the collapsed version shows them.
error = Error("field_or_constant_has_multiple_whitepsace", self.filename, line_number, line)
if not "field_or_constant_has_multiple_whitepsace" in self.errors:
self.errors["field_or_constant_has_multiple_whitepsace"] = []
self.errors["field_or_constant_has_multiple_whitepsace"].append(error)
fieldOrConstant = stripped_fieldOrConstant
comment = None
if "#" in line:
commentExtract = line.split("#", 1) # Split once on left-most '#'
fieldOrConstant = commentExtract[0].strip()
comment = commentExtract[-1].strip()
if "=" not in fieldOrConstant:
# Is a field:
field = fieldOrConstant.split(" ")
type = field[0].strip()
name = field[1].strip()
field = MessageField(name, type, comment, line_number, parentMessage)
self.fields.append(field)
else:
temp = fieldOrConstant.split("=")
value = temp[-1]
typeAndName = temp[0].split(" ")
type = typeAndName[0]
name = typeAndName[1]
if name.startswith("VEHICLE_CMD_") and parentMessage.name == 'VehicleCommand': #it's a command.
#print(f"DEBUG: startswith VEHICLE_CMD_ {name}")
commandConstant = CommandConstant(name, type, value, comment, line_number, parentMessage)
#commandConstant.display_info()
self.commandConstants[name]=commandConstant
else: #it's a constant (or part of an enum)
constantField = ConstantValue(name, type, value, comment, line_number)
self.constantFields[name]=constantField
def parseFile(self):
initial_block_lines = []
#stopping_token = None
found_first_relevant_content = False
gettingInitialComments = False
gettingFields = False
with open(self.msg_filename, 'r', encoding='utf-8') as uorbfile:
lines = uorbfile.read().splitlines()
for line_number, line in enumerate(lines, 1):
if line != line.rstrip():
#print(f"[{self.filename}] Trailing whitespace on line {line_number}: XX{line}YY")
error = Error("trailing_whitespace", self.filename, line_number, line)
if not "trailing_whitespace" in self.errors:
self.errors["trailing_whitespace"] = []
self.errors["trailing_whitespace"].append(error)
#print(f"line: {line}")
stripped_line = re.sub(r'\s+', ' ', line).strip() # Collapse all spaces to a single space and strip stuff off end.
#print(f"stripped_line: {stripped_line}")
# TODO? Perhaps report whitespace if the size of those two is different and it is empty
# Or perhaps we just fix it on request
isEmptyLine = False if line.strip() else True
if not found_first_relevant_content and isEmptyLine: #Empty line
#print(f"{self.filename}: Empty line at start of file: [{line_number}]\n {line}")
error = Error("empty_start_line", self.filename, line_number, line)
if not "empty_start_line" in self.errors:
self.errors["empty_start_line"] = []
self.errors["empty_start_line"].append(error)
#error.display_error()
continue
if not found_first_relevant_content and not isEmptyLine:
found_first_relevant_content = True
if stripped_line.startswith("#"):
gettingInitialComments = True
else:
gettingInitialComments = False
gettingFields = True
if gettingInitialComments and stripped_line.startswith("#"):
stripped_line=stripped_line[1:].strip()
#print(f"DEBUG: gettingInitialComments: comment line: {stripped_line}")
initial_block_lines.append(stripped_line)
else:
gettingInitialComments = False
gettingFields = True #Getting fields and constants
if gettingFields:
if isEmptyLine:
continue # empty line
if stripped_line.startswith("# TOPICS "):
stripped_line = stripped_line[9:]
stripped_line = stripped_line.split(" ")
self.topics+= stripped_line
# Note, default topic and topic errors handled after all lines parsed
continue
if stripped_line.startswith("#"):
# Its an internal comment
stripped_line=stripped_line[1:].strip()
if stripped_line:
#print(f"{self.filename}: Internal comment: [{line_number}]\n {line}")
error = Error("internal_comment", self.filename, line_number, line)
if not "internal_comment" in self.errors:
self.errors["internal_comment"] = []
self.errors["internal_comment"].append(error)
else:
#print(f"{self.filename}: Empty internal comment: [{line_number}]\n {line}")
error = Error("internal_comment_empty", self.filename, line_number, line)
if not "internal_comment_empty" in self.errors:
self.errors["internal_comment_empty"] = []
self.errors["internal_comment_empty"].append(error)
#pass # Empty comment
continue
# Must be a field or a comment.
self.handleField(line, line_number, parentMessage=self)
# Fix up topics if the topic is empty
def camel_to_snake(name):
# Match upper case not at start of string
s1 = re.sub('(.)([A-Z][a-z]+)', r'\1_\2', name)
# Handle cases with multiple capital first letter
return re.sub('([A-Z]+)([A-Z][a-z]*)', r'\1_\2', s1).lower()
defaultTopic = camel_to_snake(self.name)
if len(self.topics) == 0:
# We have no topic declared, so set the default topic
self.topics.append(defaultTopic)
elif len(self.topics) == 1:
# We have 1 topic declared - either it is default or there is some issue.
if defaultTopic in self.topics:
# Declared topic is default topic
error = Error("topic_error", self.filename, "", f"WARNING: TOPIC {defaultTopic} unnecessarily declared for {self.name}")
else:
# Declared topic is not default topic
error = Error("topic_error", self.filename, "", f"NOTE: TOPIC {self.topics[1]}: Only Declared topic is not default topic {defaultTopic} for {self.name}")
if not "topic_error" in self.errors:
self.errors["topic_error"] = []
self.errors["topic_error"].append(error)
elif len(self.topics) > 1:
if defaultTopic not in self.topics:
error = Error("topic_error", self.filename, "", f"NOTE: TOPIC - Default topic {defaultTopic} for {self.name} not in {self.topics}")
# Parse our short and long description
#print(f"DEBUG: initial_block_lines: {initial_block_lines}")
doingLongDescription = False
for summaryline in initial_block_lines:
if not self.shortDescription and summaryline.strip() == '':
continue
if not doingLongDescription and not summaryline.strip() == '':
self.shortDescription += f" {summaryline}"
self.shortDescription = self.shortDescription.strip()
if not self.shortDescription[-1:] == ".": # Add terminating fullstop if not present.
self.shortDescription += "."
if not doingLongDescription and summaryline.strip() == '':
doingLongDescription = True
continue
if doingLongDescription:
self.longDescription += f"{summaryline}\n"
if self.longDescription:
self.longDescription.strip()
if not self.shortDescription:
# Summary has not been defined
error = Error("summary_missing", self.filename)
if not "summary_missing" in self.errors:
self.errors["summary_missing"] = []
self.errors["summary_missing"].append(error)
# TODO Parse our constantValues into enums, leaving only constants
constantValuesToRemove = []
#print(f"DEBUG: Self.enums: {self.enums}")
for enumName, enumObject in self.enums.items():
for enumValueName, enumValueObject in self.constantFields.items():
if enumValueName.startswith(enumName):
# Copy this value into the object (cant be duplicate because parent is dict)
enumObject.enumValues[enumValueName]=enumValueObject
constantValuesToRemove.append(enumValueName)
# Now delete the original enumvalues
for enumValName in constantValuesToRemove:
del self.constantFields[enumValName]
constantsNotAssignedToEnums = len(self.constantFields)
if constantsNotAssignedToEnums > 0:
#print(f"Debug: WARNING constantsNotAssignedToEnums: {constantsNotAssignedToEnums}")
for enumValueName, enumValue in self.constantFields.items():
if enumValueName in ALLOWED_CONSTANTS_NOT_IN_ENUM: # Ignore constants
pass
else:
error = Error("constant_not_in_assigned_enum", self.filename, enumValue.line_number, enumValueName)
if not "constant_not_in_assigned_enum" in self.errors:
self.errors["constant_not_in_assigned_enum"] = []
self.errors["constant_not_in_assigned_enum"].append(error)
# TODO Maybe present as list of possible enums.
import yaml
@ -127,83 +924,50 @@ if __name__ == "__main__":
parser = argparse.ArgumentParser(description='Generate docs from .msg files')
parser.add_argument('-d', dest='dir', help='output directory', required=True)
parser.add_argument('-e', dest='errors', action='store_true', help='Report errors')
parser.add_argument('-m', dest='error_messages', help='Message to report errors against (by default all)')
args = parser.parse_args()
output_dir = args.dir
if not os.path.isdir(output_dir):
print(f"making output_dir {output_dir}")
os.mkdir(output_dir)
msg_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../../msg")
msg_files = get_msgs_list(msg_path)
msg_files.sort()
versioned_msgs_list = ''
unversioned_msgs_list = ''
msgTypes = set()
for msg_file in msg_files:
# Add messages to set of allowed types (compound types)
#msg_type = msg_file.rsplit('/')[-1]
#msg_type = msg_type.rsplit('\\')[-1]
#msg_type = msg_type.rsplit('.')[0]
msg_name = os.path.splitext(os.path.basename(msg_file))[0]
output_file = os.path.join(output_dir, msg_name+'.md')
msg_filename = os.path.join(msg_path, msg_file)
print("{:} -> {:}".format(msg_filename, output_file))
msgTypes.add(msg_name)
#Format msg url
msg_url="[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/%s)" % msg_file
msg_description = ""
summary_description = ""
#Get msg description (first non-empty comment line from top of msg)
with open(msg_filename, 'r') as lineparser:
line = lineparser.readline()
while line.startswith('#') or (line.strip() == ''):
print('DEBUG: line: %s' % line)
line=line[1:].strip()+'\n'
stripped_line=line.strip()
if msg_description and not summary_description and stripped_line=='':
summary_description = msg_description.strip()
msg_description+=line
line = lineparser.readline()
msg_description=msg_description.strip()
if not summary_description and msg_description:
summary_description = msg_description
print('msg_description: Z%sZ' % msg_description)
print('summary_description: Z%sZ' % summary_description)
summary_description
msg_contents = ""
#Get msg contents (read the file)
with open(msg_filename, 'r') as source_file:
msg_contents = source_file.read()
#Format markdown using msg name, comment, url, contents.
markdown_output="""# %s (UORB message)
%s
%s
```c
%s
```
""" % (msg_name, msg_description, msg_url, msg_contents)
with open(output_file, 'w') as content_file:
content_file.write(markdown_output)
for msg_file in msg_files:
message = UORBMessage(msg_file)
# Any additional tests that can't be in UORBMessage parser go here.
message.markdown_out()
# Categorize as versioned or unversioned
if "versioned" in msg_file:
versioned_msgs_list += '- [%s](%s.md)' % (msg_name, msg_name)
if summary_description:
versioned_msgs_list += "%s" % summary_description
versioned_msgs_list += f"- [{message.name}]({message.name}.md)"
if message.shortDescription:
versioned_msgs_list += f"{message.shortDescription}"
versioned_msgs_list += "\n"
else:
unversioned_msgs_list += '- [%s](%s.md)' % (msg_name, msg_name)
if summary_description:
unversioned_msgs_list += "%s" % summary_description
unversioned_msgs_list += f"- [{message.name}]({message.name}.md)"
if message.shortDescription:
unversioned_msgs_list += f"{message.shortDescription}"
unversioned_msgs_list += "\n"
# Write out the index.md file
index_text="""# uORB Message Reference
index_text=f"""# uORB Message Reference
::: info
This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
@ -218,14 +982,14 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
## Versioned Messages
%s
{versioned_msgs_list}
## Unversioned Messages
%s
""" % (versioned_msgs_list, unversioned_msgs_list)
{unversioned_msgs_list}
"""
index_file = os.path.join(output_dir, 'index.md')
with open(index_file, 'w') as content_file:
with open(index_file, 'w', encoding='utf-8') as content_file:
content_file.write(index_text)
generate_dds_yaml_doc(msg_files)

View File

@ -259,6 +259,9 @@ PX4_USB_IDS: list[tuple[int, int, str]] = [
(0x0483, 0x5740, "STMicroelectronics Virtual COM Port"), # Generic ST bootloader
(0x1209, 0x5740, "Generic STM32"),
(0x1209, 0x5741, "ArduPilot"),
(0x3185, 0x0039, "ARK FMU v6x"),
(0x3185, 0x003A, "ARK Pi6x"),
(0x3185, 0x003B, "ARK FPV"),
(0x2341, 0x8036, "Arduino Leonardo"), # Some PX4 boards use this
]

@ -1 +1 @@
Subproject commit ac718b6fb2d6b337248e23702e75d6d1e2125054
Subproject commit 5b6966ed572a02e8273f446acb504a45a841ca53

@ -1 +1 @@
Subproject commit 66b764ada522893c05224950aa6268c809f8e48a
Subproject commit 665b26d62d36a33b6bf01c5931c589beb812c6a2

View File

@ -31,6 +31,7 @@ CONFIG_UAVCANNODE_ESC_RAW_COMMAND=y
CONFIG_UAVCANNODE_ESC_STATUS=y
CONFIG_UAVCANNODE_FLOW_MEASUREMENT=y
CONFIG_UAVCANNODE_GNSS_FIX=y
CONFIG_UAVCANNODE_HARDPOINT_COMMAND=y
CONFIG_UAVCANNODE_HYGROMETER_MEASUREMENT=y
CONFIG_UAVCANNODE_LIGHTS_COMMAND=y
CONFIG_UAVCANNODE_MAGNETIC_FIELD_STRENGTH=y

View File

@ -1,4 +1,6 @@
# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set
CONFIG_DRIVERS_UAVCAN=n
CONFIG_MODULES_UXRCE_DDS_CLIENT=n
CONFIG_SYSTEMCMDS_SD_BENCH=n
CONFIG_SYSTEMCMDS_I2CDETECT=n
CONFIG_MODULES_ZENOH=y

View File

@ -0,0 +1,3 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROMFSROOT=""

View File

@ -0,0 +1,86 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROOT_PATH="/fs/flash"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS2"
CONFIG_BOARD_SERIAL_RC="/dev/ttyS1"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_DPS310=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_AUX_GLOBAL_POSITION is not set
# CONFIG_EKF2_AUXVEL is not set
# CONFIG_EKF2_BARO_COMPENSATION is not set
# CONFIG_EKF2_DRAG_FUSION is not set
# CONFIG_EKF2_GNSS_YAW is not set
# CONFIG_EKF2_SIDESLIP is not set
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_MODE_MANAGER=y
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y

View File

@ -0,0 +1,13 @@
{
"board_id": 1209,
"magic": "PX4FWv1",
"description": "Firmware for the AirBrainH743 by Gear Up",
"image": "",
"build_time": 0,
"summary": "AirBrainH743",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1966080,
"git_identity": "",
"board_revision": 0
}

View File

@ -0,0 +1,17 @@
#!/bin/sh
#
# AirBrainH743 board specific defaults
#------------------------------------------------------------------------------
# Battery voltage divider and current scale
param set-default BAT1_V_DIV 15.0
param set-default BAT1_A_PER_V 101.0
# system_power unavailable
param set-default CBRK_SUPPLY_CHK 894281
param set-default IMU_GYRO_RATEMAX 2000
# W25N NAND flash with littlefs (128 MB): larger buffer, auto-rotate
set LOGGER_BUF 32
param set-default SDLOG_DIRS_MAX 3

View File

@ -0,0 +1,6 @@
#!/bin/sh
#
# AirBrainH743 specific board extras init
#------------------------------------------------------------------------------
# No extras configured by default

View File

@ -0,0 +1,16 @@
#!/bin/sh
#
# AirBrainH743 specific board sensors init
#------------------------------------------------------------------------------
board_adc start
# Internal SPI bus IMU - ICM42688P (Invensensev3)
icm42688p -R 2 -b 1 -s start
# Internal I2C bus barometer - DPS310 @ 0x76 (118 decimal)
dps310 -I -a 118 start
# Internal I2C bus magnetometer - LIS2MDL @ 0x1E (30 decimal)
# Using iis2mdc driver (functionally equivalent to LIS2MDL)
iis2mdc -I -R 2 -a 30 start

View File

@ -0,0 +1,3 @@
#
# Board-specific Kconfig for AirBrainH743
#

View File

@ -0,0 +1,89 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DEV_CONSOLE is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_SPI_EXCHANGE is not set
# CONFIG_STM32H7_SYSCFG is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/gearup/airbrainh743/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_INITTHREAD_PRIORITY=254
CONFIG_BOARD_LATE_INITIALIZE=y
CONFIG_BOARD_LOOPSPERMSEC=22114
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x004b
CONFIG_CDCACM_PRODUCTSTR="AirBrainH743 BL"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORSTR="Gear Up"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEFAULT_SMALL=y
CONFIG_EXPERIMENTAL=y
CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_INIT_ENTRYPOINT="bootloader_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SPI=y
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_USART1=y
CONFIG_SYSTEMTICK_HOOK=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGINT_CHAR=0x03
CONFIG_TTY_SIGTSTP=y
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=300
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000

View File

@ -0,0 +1,346 @@
/************************************************************************************
* nuttx-config/include/board.h
*
* Copyright (C) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_AIRBRAINH743_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_AIRBRAINH743_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include "board_dma_map.h"
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
#include "stm32_rcc.h"
#include "stm32_sdmmc.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* The AirBrainH743 board provides the following clock sources:
*
* X1: 8 MHz crystal for HSE
*/
#define STM32_BOARD_XTAL 8000000ul
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 32768
/* Main PLL Configuration.
*
* PLL source is HSE = 8,000,000
*
* PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN
*
* SYSCLK = PLL_VCO / PLLP
* CPUCLK = SYSCLK / D1CPRE
*/
#define STM32_BOARD_USEHSE
#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
*
* PLL1_VCO = (8,000,000 / 1) * 120 = 960 MHz
*
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz
*/
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \
RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP1EN | \
RCC_PLLCFGR_DIVQ1EN | \
RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1)
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120)
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(5)
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120)
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 5)
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
/* PLL2 */
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP2EN | \
RCC_PLLCFGR_DIVQ2EN | \
RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2)
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48)
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2)
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2)
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48)
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
/* PLL3 */
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \
RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVQ3EN)
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2)
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48)
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4)
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2)
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48)
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4)
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
/* SYSCLK = PLL1P = 480MHz
* CPUCLK = SYSCLK / 1 = 480 MHz
*/
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
/* Configure Clock Assignments */
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240
*/
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB4 clock (PCLK4) is HCLK/2 (120 MHz) */
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timer clock frequencies */
/* Timers driven from APB1 will be twice PCLK1 */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* Timers driven from APB2 will be twice PCLK2 */
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
/* Kernel Clock Configuration */
/* I2C123 clock source */
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI
/* I2C4 clock source */
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
/* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
/* SPI45 clock source */
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2
/* SPI6 clock source */
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2
/* USB 1 and 2 clock source */
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3
/* ADC 1 2 3 clock source */
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2
/* FDCAN 1 clock source */
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE
#define STM32_FDCANCLK STM32_HSE_FREQUENCY
/* FLASH wait states */
#define BOARD_FLASH_WAITSTATES 2
/* LED definitions ******************************************************************/
#define BOARD_LED1 0
#define BOARD_LED2 1
#define BOARD_LED3 2
#define BOARD_NLEDS 3
#define BOARD_LED_RED BOARD_LED1
#define BOARD_LED_GREEN BOARD_LED2
#define BOARD_LED_BLUE BOARD_LED3
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
#define BOARD_LED3_BIT (1 << BOARD_LED3)
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
/* Alternate function pin selections ************************************************/
/* USART1 - Debug (PA9 TX, PA10 RX) */
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */
/* USART2 - RC input (PD5 TX, PD6 RX) */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
/* USART3 - DJI/MSP (PD8 TX, PD9 RX) */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
/* UART4 - General (PB9 TX, PB8 RX) */
#define GPIO_UART4_RX GPIO_UART4_RX_3 /* PB8 */
#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PB9 */
/* UART5 - Companion (PB13 TX, PB12 RX) */
#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PB12 */
#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */
/* UART7 - ESC telemetry (PE8 TX, PE7 RX) */
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
/* UART8 - GPS (PE1 TX, PE0 RX) */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* SPI
*
* SPI1: IMU (PA5 SCK, PA6 MISO, PA7 MOSI)
* SPI2: W25N Flash (PD3 SCK, PB14 MISO, PC3 MOSI)
* SPI4: External (PE12 SCK, PE5 MISO, PE6 MOSI)
*/
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_5 /* PD3 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE12 */
/* I2C
*
* I2C1: Internal (PB6 SCL, PB7 SDA)
* I2C4: External (PD12 SCL, PD13 SDA)
*/
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 /* PB6 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_1 /* PD12 */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_1 /* PD13 */
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN12)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN13)
/* USB
*
* OTG_FS_DM PA11
* OTG_FS_DP PA12
* VBUS PD0
*/
#endif /*__NUTTX_CONFIG_AIRBRAINH743_INCLUDE_BOARD_H */

View File

@ -0,0 +1,42 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/* DMA mapping for SPI1 (IMU) */
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
/* DMA mapping for SPI2 (W25N Flash) */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */

View File

@ -0,0 +1,258 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CP is not set
# CONFIG_NSH_DISABLE_DATE is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_ENV is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_EXPORT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MV is not set
# CONFIG_NSH_DISABLE_PRINTF is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
# CONFIG_NSH_DISABLE_PWD is not set
# CONFIG_NSH_DISABLE_RM is not set
# CONFIG_NSH_DISABLE_RMDIR is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_SOURCE is not set
# CONFIG_NSH_DISABLE_TEST is not set
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set
# CONFIG_SPI_CALLBACK is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/gearup/airbrainh743/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0050
CONFIG_CDCACM_PRODUCTSTR="AirBrainH743"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORSTR="Gear Up"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_FS_LITTLEFS=y
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_LITTLEFS_READ_SIZE_FACTOR=1
CONFIG_FS_LITTLEFS_CACHE_SIZE_FACTOR=1
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_MAX_EXITFUNS=1
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MM_REGIONS=4
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_W25N=y
CONFIG_W25N_SPIFREQUENCY=104000000
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC3=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BDMA=y
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_DMAMUX1=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C4=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=4096
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM2=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM5=y
CONFIG_STM32H7_TIM8=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART5=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART1=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART5_BAUD=57600
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_WATCHDOG=y

View File

@ -0,0 +1,213 @@
/****************************************************************************
* scripts/script.ld
*
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory.
* The flash memory is partitioned into a User Flash memory and a System
* Flash memory. Each of these memories has two banks:
*
* 1) User Flash memory:
*
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
*
* 2) System Flash memory:
*
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
*
* 3) User option bytes for user configuration, only in Bank 1.
*
* In the STM32H743II, two different boot spaces can be selected through
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
* BOOT_ADD1 option bytes:
*
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
* ST programmed value: Flash memory at 0x0800:0000
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
* ST programmed value: System bootloader at 0x1FF0:0000
*
* The Durandal has a Switch on board, the BOOT0 pin is at ground so by default,
* the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is
* drepresed, then the boot will be from 0x1FF0:0000
*
* The STM32H743ZI also has 1024Kb of data SRAM.
* SRAM is split up into several blocks and into three power domains:
*
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
*
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
*
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
* DTCM ports. The DTCM-RAM could be used for critical real-time
* data, such as interrupt service routines or stack / heap memory.
* Both DTCM-RAMs can be used in parallel (for load/store operations)
* thanks to the Cortex-M7 dual issue capability.
*
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
*
* This RAM is connected to ITCM 64-bit interface designed for
* execution of critical real-times routines by the CPU.
*
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
* through D1 domain AXI bus matrix
*
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
*
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
* through D2 domain AHB bus matrix
*
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
*
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
*
* 4) AHB SRAM (D3 domain) accessible by most of system masters
* through D3 domain AHB bus matrix
*
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*/
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,228 @@
/****************************************************************************
* scripts/script.ld
*
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The board uses an STM32H743II and has 2048Kb of main FLASH memory.
* The flash memory is partitioned into a User Flash memory and a System
* Flash memory. Each of these memories has two banks:
*
* 1) User Flash memory:
*
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
*
* 2) System Flash memory:
*
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
*
* 3) User option bytes for user configuration, only in Bank 1.
*
* In the STM32H743II, two different boot spaces can be selected through
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
* BOOT_ADD1 option bytes:
*
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
* ST programmed value: Flash memory at 0x0800:0000
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
* ST programmed value: System bootloader at 0x1FF0:0000
*
* There's a switch on board, the BOOT0 pin is at ground so by default,
* the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is
* drepresed, then the boot will be from 0x1FF0:0000
*
* The STM32H743ZI also has 1024Kb of data SRAM.
* SRAM is split up into several blocks and into three power domains:
*
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
*
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
*
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
* DTCM ports. The DTCM-RAM could be used for critical real-time
* data, such as interrupt service routines or stack / heap memory.
* Both DTCM-RAMs can be used in parallel (for load/store operations)
* thanks to the Cortex-M7 dual issue capability.
*
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
*
* This RAM is connected to ITCM 64-bit interface designed for
* execution of critical real-times routines by the CPU.
*
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
* through D1 domain AXI bus matrix
*
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
*
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
* through D2 domain AHB bus matrix
*
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
*
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
*
* 4) AHB SRAM (D3 domain) accessible by most of system masters
* through D3 domain AHB bus matrix
*
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*/
MEMORY
{
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > FLASH
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
. = ALIGN(16);
FILL(0xffff)
. += 16;
} > AXI_SRAM AT > FLASH = 0xffff
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
.sram4_reserve (NOLOAD) :
{
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,67 @@
############################################################################
#
# Copyright (c) 2026 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
add_library(drivers_board
bootloader_main.c
usb.c
)
target_link_libraries(drivers_board
PRIVATE
nuttx_arch
nuttx_drivers
bootloader
)
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
else()
add_library(drivers_board
i2c.cpp
init.c
led.c
spi.cpp
timer_config.cpp
usb.c
)
add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_io_pins
arch_spi
arch_board_hw_info
drivers__led
nuttx_arch
nuttx_drivers
px4_layer
)
endif()

View File

@ -0,0 +1,223 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* AirBrainH743 (Gear Up) internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* Enable small flash logging support (for W25N NAND flash) */
#ifdef CONFIG_MTD_W25N
# define BOARD_SMALL_FLASH_LOGGING 1
#endif
/* LEDs are active low
* STAT RGB LED:
* PB15 = Blue
* PD11 = Green
* PD15 = Red
* BAT LED (orange): hardwired to power input
*/
#define GPIO_nLED_BLUE /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
#define GPIO_nLED_GREEN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11)
#define GPIO_nLED_RED /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN15)
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_OVERLOAD_LED LED_RED
#define BOARD_ARMED_STATE_LED LED_GREEN
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that
* can be used by the Px4 Firmware in the adc driver
*/
/* ADC defines to be used in sensors.cpp to read from a particular channel */
#define ADC1_CH(n) (n)
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
#define PX4_ADC_GPIO \
/* PC4 */ GPIO_ADC12_INP4, \
/* PC5 */ GPIO_ADC12_INP8
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC4 */ ADC1_CH(4)
#define ADC_BATTERY_CURRENT_CHANNEL /* PC5 */ ADC1_CH(8)
#define ADC_CHANNELS \
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY_CURRENT_CHANNEL))
/* Define Battery Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (15.0f)
#define BOARD_BATTERY1_A_PER_V (101.0f)
/* PWM
* 8 PWM outputs for motors + 1 for LED strip
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 9
#define DIRECT_INPUT_TIMER_CHANNELS 9
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* Tone alarm output (directly connected to transistor switch of external buzzer)
*
* GPIO mode only (active buzzer) - passive buzzer with different tones is not
* supported because PA15 can only use TIM2, which is also used for motor outputs
* M7 (PB10, TIM2_CH3) and M8 (PB11, TIM2_CH4). The PWM tone alarm driver changes
* the timer's prescaler and auto-reload registers (shared across all channels),
* which would affect M7/M8 PWM frequency during tone playback.
*/
#define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
#define GPIO_TONE_ALARM_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15)
/* ICM42688P FSYNC - directly connected to IMU via GPIO (no timer).
* The driver clears TMST_FSYNC_EN and FIFO_TMST_FSYNC_EN, so FSYNC is unused.
* This GPIO is kept low to prevent spurious triggers.
*/
#define GPIO_42688P_FSYNC /* PC7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN7)
/* USB OTG FS
*
* PD0 VBUS sensing (active high input)
*/
#define GPIO_OTGFS_VBUS /* PD0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN0)
/* High-resolution timer */
#define HRT_TIMER 8 /* use timer8 for the HRT */
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
/*
* Serial Port Mapping:
*
* UART Device Pins Function
* ---- ------ ---- --------
* USART1 /dev/ttyS0 PA9/PA10 Console/Debug
* USART2 /dev/ttyS1 PD5/PD6 RC Input
* USART3 /dev/ttyS2 PD8/PD9 TEL4 (DJI/MSP)
* UART4 /dev/ttyS3 PA0/PA1 TEL1
* UART5 /dev/ttyS4 PB13/PB12 TEL2
* UART7 /dev/ttyS5 PE8/PE7 TEL3 (ESC Telemetry)
* UART8 /dev/ttyS6 PE1/PE0 GPS1
*/
/* RC Serial port - USART2 (PD5/PD6) */
#define RC_SERIAL_PORT "/dev/ttyS1"
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_nLED_RED, \
GPIO_nLED_GREEN, \
GPIO_nLED_BLUE, \
GPIO_TONE_ALARM_IDLE, \
GPIO_42688P_FSYNC, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 4
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the board.
*
****************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
/* Parameters stored in internal flash */
#define FLASH_BASED_PARAMS
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@ -0,0 +1,75 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file bootloader_main.c
*
* AirBrainH743-specific early startup code for bootloader
*/
#include "board_config.h"
#include "bl.h"
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "arm_internal.h"
#include <px4_platform_common/init.h>
extern int sercon_main(int c, char **argv);
__EXPORT void board_on_reset(int status) {}
__EXPORT void stm32_boardinitialize(void)
{
/* configure USB interfaces */
stm32_usbinitialize();
}
__EXPORT int board_app_initialize(uintptr_t arg)
{
return 0;
}
void board_late_initialize(void)
{
sercon_main(0, NULL);
}
extern void sys_tick_handler(void);
void board_timerhook(void)
{
sys_tick_handler();
}

View File

@ -0,0 +1,85 @@
/****************************************************************************
*
* Copyright (C) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#define APP_LOAD_ADDRESS 0x08020000
#define BOOTLOADER_DELAY 5000
#define INTERFACE_USB 1
#define INTERFACE_USB_CONFIG "/dev/ttyACM0"
#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS)
#define INTERFACE_USART 1
#define INTERFACE_USART_CONFIG "/dev/ttyS0,57600"
#define BOOT_DELAY_ADDRESS 0x000001a0
#define BOARD_TYPE 1209
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
#define BOARD_FLASH_SECTORS (14)
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
#define OSC_FREQ 8
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN
#define BOARD_LED_ON 0
#define BOARD_LED_OFF 1
#define SERIAL_BREAK_DETECT_DISABLED 1
#if !defined(ARCH_SN_MAX_LENGTH)
# define ARCH_SN_MAX_LENGTH 12
#endif
/* Reserve 128KB (1 sector) at end of flash for parameters */
#define APP_RESERVATION_SIZE (1 * 128 * 1024)
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE)
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1
#endif
#if !defined(USB_DATA_ALIGN)
# define USB_DATA_ALIGN
#endif
#ifndef BOOT_DEVICES_SELECTION
# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
#endif
#ifndef BOOT_DEVICES_FILTER_ONUSB
# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
#endif
/* Boot device selection list*/
#define USB0_DEV 0x01
#define SERIAL0_DEV 0x02
#define SERIAL1_DEV 0x04

View File

@ -0,0 +1,47 @@
/****************************************************************************
*
* Copyright (C) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/i2c_hw_description.h>
/*
* I2C bus configuration for AirBrainH743
*
* I2C1: Internal bus - PB6 (SCL), PB7 (SDA)
* Devices: DPS310 baro @ 0x76, LIS2MDL compass @ 0x1E
* I2C4: External bus - PD12 (SCL), PD13 (SDA)
*/
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusInternal(1),
initI2CBusExternal(4),
};

View File

@ -0,0 +1,249 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file init.c
*
* AirBrainH743-specific early startup code.
*/
#include "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <fcntl.h>
#include <unistd.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/mtd/mtd.h>
#include <nuttx/fs/fs.h>
#include <arch/board/board.h>
#include "arm_internal.h"
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_arch/io_timer.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#if defined(FLASH_BASED_PARAMS)
#include <parameters/flashparams/flashfs.h>
#endif
#ifdef CONFIG_MTD_W25N
extern FAR struct mtd_dev_s *w25n_initialize(FAR struct spi_dev_s *dev, uint32_t spi_devid);
#endif
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
UNUSED(ms);
}
/************************************************************************************
* Name: board_on_reset
*
* Description:
* Optionally provided function called on entry to board_system_reset
* It should perform any house keeping prior to the rest.
*
* status - 1 if resetting to boot loader
* 0 if just resetting
*
************************************************************************************/
__EXPORT void board_on_reset(int status)
{
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
}
if (status >= 0) {
up_mdelay(100);
}
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
/* Reset PWM first thing */
board_on_reset(-1);
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure USB interfaces */
stm32_usbinitialize();
}
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Need hrt running before using the ADC */
px4_platform_init();
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
/* initial LED state */
drv_led_start();
led_off(LED_RED);
led_off(LED_GREEN);
led_off(LED_BLUE);
if (board_hardfault_init(2, true) != 0) {
led_on(LED_RED);
}
#ifdef CONFIG_MTD_W25N
/* Initialize W25N01GV NAND Flash on SPI2 */
struct spi_dev_s *spi2 = stm32_spibus_initialize(2);
if (!spi2) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI2 for W25N\n");
led_on(LED_RED);
} else {
struct mtd_dev_s *mtd = w25n_initialize(spi2, 0);
if (!mtd) {
syslog(LOG_ERR, "[boot] FAILED to initialize W25N MTD driver\n");
led_on(LED_RED);
} else {
int ret = register_mtddriver("/dev/mtd0", mtd, 0755, NULL);
if (ret < 0) {
syslog(LOG_ERR, "[boot] FAILED to register MTD driver: %d\n", ret);
led_on(LED_RED);
} else {
syslog(LOG_INFO, "[boot] W25N MTD registered at /dev/mtd0\n");
#ifdef CONFIG_FS_LITTLEFS
ret = nx_mount("/dev/mtd0", CONFIG_BOARD_ROOT_PATH, "littlefs", 0, NULL);
if (ret == 0) {
/* Verify the filesystem is usable by creating a test file */
int fd = open(CONFIG_BOARD_ROOT_PATH "/.mount_test", O_CREAT | O_WRONLY | O_TRUNC);
if (fd >= 0) {
close(fd);
unlink(CONFIG_BOARD_ROOT_PATH "/.mount_test");
} else {
syslog(LOG_WARNING, "[boot] littlefs mounted but not usable, reformatting\n");
nx_umount2(CONFIG_BOARD_ROOT_PATH, 0);
ret = -1;
}
}
if (ret < 0) {
ret = nx_mount("/dev/mtd0", CONFIG_BOARD_ROOT_PATH, "littlefs", 0, "forceformat");
}
if (ret < 0) {
syslog(LOG_ERR, "[boot] FAILED to mount littlefs: %d\n", ret);
led_on(LED_RED);
} else {
syslog(LOG_INFO, "[boot] LittleFS mounted at %s\n", CONFIG_BOARD_ROOT_PATH);
}
#endif
}
}
}
#endif
#if defined(FLASH_BASED_PARAMS)
/* Initialize parameters in internal flash (sector 15, 128KB at 0x081E0000) */
static sector_descriptor_t params_sector_map[] = {
{15, 128 * 1024, 0x081E0000},
{0, 0, 0},
};
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
if (result != OK) {
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
led_on(LED_RED);
}
#endif
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
}

View File

@ -0,0 +1,205 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include "chip.h"
#include "stm32_gpio.h"
#include "board_config.h"
#include <nuttx/board.h>
#include <arch/board/board.h>
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
#ifdef CONFIG_ARCH_LEDS
static bool nuttx_owns_leds = true;
static const uint8_t xlatpx4[] = {1, 2, 4, 0};
# define xlat(p) xlatpx4[(p)]
static uint32_t g_ledmap[] = {
GPIO_nLED_RED, // Indexed by BOARD_LED_RED
GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN
GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE
};
#else
# define xlat(p) (p)
static uint32_t g_ledmap[] = {
GPIO_nLED_RED, // LED_RED
GPIO_nLED_GREEN, // LED_GREEN
GPIO_nLED_BLUE, // LED_BLUE
};
#endif
__EXPORT void led_init(void)
{
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
if (g_ledmap[l] != 0) {
stm32_configgpio(g_ledmap[l]);
}
}
}
static void phy_set_led(int led, bool state)
{
/* Drive Low to switch on (active low LEDs) */
if (led < (int)(sizeof(g_ledmap) / sizeof(g_ledmap[0])) && g_ledmap[led] != 0) {
stm32_gpiowrite(g_ledmap[led], !state);
}
}
static bool phy_get_led(int led)
{
/* If Low it is on */
if (led < (int)(sizeof(g_ledmap) / sizeof(g_ledmap[0])) && g_ledmap[led] != 0) {
return !stm32_gpioread(g_ledmap[led]);
}
return false;
}
__EXPORT void led_on(int led)
{
phy_set_led(xlat(led), true);
}
__EXPORT void led_off(int led)
{
phy_set_led(xlat(led), false);
}
__EXPORT void led_toggle(int led)
{
phy_set_led(xlat(led), !phy_get_led(xlat(led)));
}
#ifdef CONFIG_ARCH_LEDS
/****************************************************************************
* Public Functions
****************************************************************************/
void board_autoled_initialize(void)
{
led_init();
}
void board_autoled_on(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_HEAPALLOCATE:
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_IRQSENABLED:
phy_set_led(BOARD_LED_BLUE, false);
phy_set_led(BOARD_LED_GREEN, true);
break;
case LED_STACKCREATED:
phy_set_led(BOARD_LED_GREEN, true);
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_INIRQ:
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_SIGNAL:
phy_set_led(BOARD_LED_GREEN, true);
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, true);
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, true);
break;
case LED_IDLE:
phy_set_led(BOARD_LED_RED, true);
break;
}
}
void board_autoled_off(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_SIGNAL:
phy_set_led(BOARD_LED_GREEN, false);
break;
case LED_INIRQ:
phy_set_led(BOARD_LED_BLUE, false);
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, false);
phy_set_led(BOARD_LED_BLUE, false);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, false);
break;
case LED_IDLE:
phy_set_led(BOARD_LED_RED, false);
break;
}
}
#endif /* CONFIG_ARCH_LEDS */

View File

@ -0,0 +1,58 @@
/****************************************************************************
*
* Copyright (C) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
/*
* SPI bus configuration for AirBrainH743
*
* SPI1: IMU (Invensensev3/ICM42688P) - PA5 SCK, PA6 MISO, PA7 MOSI, PA3 CS
* SPI2: W25N Flash - PD3 SCK, PB14 MISO, PC3 MOSI, PD4 CS
* SPI4: External/AUX - PE12 SCK, PE5 MISO, PE6 MOSI
*/
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortA, GPIO::Pin3}),
}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin4}), // W25N Flash
}),
initSPIBusExternal(SPI::Bus::SPI4, {
initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin3}), // User 1 GPIO as chip select
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);

View File

@ -0,0 +1,74 @@
/****************************************************************************
*
* Copyright (C) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/io_timer_hw_description.h>
/*
* PWM output configuration for AirBrainH743
*
* M1: PE14 (TIM1_CH4)
* M2: PE13 (TIM1_CH3)
* M3: PE11 (TIM1_CH2)
* M4: PE9 (TIM1_CH1)
* M5: PB0 (TIM3_CH3)
* M6: PB1 (TIM3_CH4)
* M7: PB10 (TIM2_CH3)
* M8: PB11 (TIM2_CH4)
* M9: PA2 (TIM5_CH3) - LED strip
*
* Note: TIM2 is shared with buzzer pin PA15 (TIM2_CH1). The buzzer is disabled
* by default because the tone alarm driver would change the timer prescaler/ARR
* which affects M7/M8 PWM frequency. See board_config.h for details.
*/
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer1, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}),
initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}),
initIOTimer(Timer::Timer2, DMA{DMA::Index1, DMA::Stream6, DMA::Channel3}),
initIOTimer(Timer::Timer5),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), // M1
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), // M2
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), // M3
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), // M4
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), // M5
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), // M6
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortB, GPIO::Pin10}), // M7
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortB, GPIO::Pin11}), // M8
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), // M9 (LED)
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);

View File

@ -0,0 +1,75 @@
/****************************************************************************
*
* Copyright (C) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file usb.c
*
* Board-specific USB functions.
*/
#include "board_config.h"
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <stm32_otg.h>
#include <debug.h>
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO */
#ifdef CONFIG_STM32H7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*
* Description:
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
* used. This function is called whenever the USB enters or leaves suspend mode.
*
************************************************************************************/
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@ -16,36 +16,36 @@
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CP is not set
# CONFIG_NSH_DISABLE_DATE is not set
# CONFIG_NSH_DISABLE_DF is not set
CONFIG_NSH_DISABLE_DATE=y
CONFIG_NSH_DISABLE_DF=y
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_ENV is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_EXPORT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
CONFIG_NSH_DISABLE_EXPORT=y
CONFIG_NSH_DISABLE_FREE=y
CONFIG_NSH_DISABLE_GET=y
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
CONFIG_NSH_DISABLE_MKDIR=y
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MV is not set
# CONFIG_NSH_DISABLE_PRINTF is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
# CONFIG_NSH_DISABLE_PWD is not set
CONFIG_NSH_DISABLE_PRINTF=y
CONFIG_NSH_DISABLE_PS=y
CONFIG_NSH_DISABLE_PSSTACKUSAGE=y
CONFIG_NSH_DISABLE_PWD=y
# CONFIG_NSH_DISABLE_RM is not set
# CONFIG_NSH_DISABLE_RMDIR is not set
CONFIG_NSH_DISABLE_RMDIR=y
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_SOURCE is not set
# CONFIG_NSH_DISABLE_TEST is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_NSH_DISABLE_TIME=y
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set

View File

@ -1,5 +1,6 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROOT_PATH="/fs/flash"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"

View File

@ -38,5 +38,6 @@ param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# Disable logging
param set-default SDLOG_BACKEND 0
# W25N NAND flash with littlefs (128 MB): larger buffer, auto-rotate
set LOGGER_BUF 32
param set-default SDLOG_DIRS_MAX 3

View File

@ -99,7 +99,7 @@
* PLL1_VCO = (8,000,000 / 1) * 120 = 960 MHz
*
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
* PLL1Q = PLL1_VCO/5 = 960 MHz / 5 = 192 MHz (SPI123 clock, max 200 MHz)
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz
*/
@ -111,12 +111,12 @@
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1)
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120)
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(5)
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120)
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 5)
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
/* PLL2 */
@ -227,9 +227,9 @@
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
/* SPI123 clock source */
/* SPI123 clock source - PLL1Q = 192 MHz for W25N NAND flash (max 104 MHz) */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL1
/* SPI45 clock source */
@ -281,17 +281,17 @@
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
/* 25 MHz Max for now, 25 mHz = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* PLL1Q = 192 MHz, div = 192 / 50 = 3.84, round up to 4 for 24 MHz
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
# define STM32_SDMMC_MMCXFR_CLKDIV (4 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
# define STM32_SDMMC_SDXFR_CLKDIV (4 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif

View File

@ -33,6 +33,10 @@
#pragma once
/* SPI1 DMA for W25N NAND Flash */
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1 */
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */

View File

@ -104,6 +104,10 @@ CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_FS_LITTLEFS=y
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_LITTLEFS_READ_SIZE_FACTOR=1
CONFIG_FS_LITTLEFS_CACHE_SIZE_FACTOR=1
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
@ -126,7 +130,9 @@ CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_RAMTRON=y
# CONFIG_MTD_RAMTRON is not set
CONFIG_MTD_W25N=y
CONFIG_W25N_SPIFREQUENCY=104000000
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
@ -135,7 +141,7 @@ CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_MMCSDSPIPORTNO=1
# CONFIG_NSH_MMCSDSPIPORTNO is not set
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
@ -148,9 +154,6 @@ CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
@ -188,6 +191,7 @@ CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_DMAMUX1=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
@ -202,6 +206,8 @@ CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=4096
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y

View File

@ -59,6 +59,11 @@
# define BOARD_HAS_NBAT_V 1
# define BOARD_HAS_NBAT_I 1
/* Enable small flash logging support (for W25N NAND flash) */
#ifdef CONFIG_MTD_W25N
# define BOARD_SMALL_FLASH_LOGGING 1
#endif
/* Holybro KakuteH7 GPIOs ************************************************************************/
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */

View File

@ -59,6 +59,8 @@
#include <nuttx/spi/spi.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include <nuttx/mtd/mtd.h>
#include <nuttx/fs/fs.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
@ -79,6 +81,10 @@
# include <parameters/flashparams/flashfs.h>
#endif
#ifdef CONFIG_MTD_W25N
extern FAR struct mtd_dev_s *w25n_initialize(FAR struct spi_dev_s *dev, uint32_t spi_devid);
#endif
/****************************************************************************
* Pre-Processor Definitions
@ -231,14 +237,49 @@ __EXPORT int board_app_initialize(uintptr_t arg)
led_on(LED_RED);
}
/* Get the SPI port for the microSD slot */
struct spi_dev_s *spi_dev = stm32_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO);
#ifdef CONFIG_MTD_W25N
/* Initialize W25N01GV NAND Flash on SPI1 */
struct spi_dev_s *spi1 = stm32_spibus_initialize(1);
if (!spi_dev) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO);
led_on(LED_BLUE);
if (!spi1) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI1 for W25N\n");
led_on(LED_RED);
} else {
struct mtd_dev_s *mtd = w25n_initialize(spi1, 0);
if (!mtd) {
syslog(LOG_ERR, "[boot] FAILED to initialize W25N MTD driver\n");
led_on(LED_RED);
} else {
int ret = register_mtddriver("/dev/mtd0", mtd, 0755, NULL);
if (ret < 0) {
syslog(LOG_ERR, "[boot] FAILED to register MTD driver: %d\n", ret);
led_on(LED_RED);
} else {
syslog(LOG_INFO, "[boot] W25N MTD registered at /dev/mtd0\n");
#ifdef CONFIG_FS_LITTLEFS
ret = nx_mount("/dev/mtd0", CONFIG_BOARD_ROOT_PATH, "littlefs", 0, "autoformat");
if (ret < 0) {
syslog(LOG_ERR, "[boot] FAILED to mount littlefs: %d\n", ret);
led_on(LED_RED);
} else {
syslog(LOG_INFO, "[boot] LittleFS mounted at %s\n", CONFIG_BOARD_ROOT_PATH);
}
#endif
}
}
}
#endif
up_udelay(20);

View File

@ -37,7 +37,7 @@
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(SPIDEV_MMCSD(0), SPI::CS{GPIO::PortA, GPIO::Pin4})
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortA, GPIO::Pin4}) // W25N01GV NAND Flash
}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}),

@ -1 +1 @@
Subproject commit 85151aaf6ba8b24ce82b387e088452c63f7e2096
Subproject commit d5abf9cbbf07711db2a9166c2eec4a4a7682f921

View File

@ -160,3 +160,44 @@
.vp-doc img {
display: inline; /* block by default set by vitepress */
}
/**
* Custom styles for wide pages
* -------------------------------------------------------------------------- */
.is-wide-page .content-container {
max-width: 100% !important;
}
@media (min-width: 1280px) {
.is-wide-page .content {
min-width: 940px !important;
}
}
/* Make page width larger */
@media (min-width: 1440px) {
.is-wide-page .VPSidebar {
padding-left: 32px !important;
width: var(--vp-sidebar-width) !important;
}
.is-wide-page .VPContent.has-sidebar {
padding-left: var(--vp-sidebar-width) !important;
padding-right: 0 !important;
}
.is-wide-page .VPNavBar.has-sidebar .title {
padding-left: 32px !important;
}
.is-wide-page .VPNavBar.has-sidebar .content {
padding-left: var(--vp-sidebar-width) !important;
padding-right: 32px !important;
}
/* Very hacky */
.is-wide-page .VPNavBar.has-sidebar #local-search {
z-index: 10;
}
}

View File

@ -178,6 +178,7 @@
- [CubePilot Cube Orange (CubePilot)](flight_controller/cubepilot_cube_orange.md)
- [CubePilot Cube Yellow (CubePilot)](flight_controller/cubepilot_cube_yellow.md)
- [Cube Wiring Quickstart](assembly/quick_start_cube.md)
- [Gear Up AirBrainH743](flight_controller/gearup_airbrainh743.md)
- [Holybro Kakute H7v2](flight_controller/kakuteh7v2.md)
- [Holybro Kakute H7mini](flight_controller/kakuteh7mini.md)
- [Holybro Kakute H7](flight_controller/kakuteh7.md)

View File

@ -106,7 +106,7 @@ The settings and underlying parameters are shown below.
| Setting | Parameter | Description |
| -------------------------------------------------------------------- | ------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None, `1`: Warning, `3`: Return mode (default). |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None (default), `1`: Warning, `3`: Return mode. |
| <a id="COM_FLT_TIME_MAX"></a> Maximum flight time failsafe level | [COM_FLT_TIME_MAX](../advanced_config/parameter_reference.md#COM_FLT_TIME_MAX) | Maximum allowed flight time before Return mode will be engaged, in seconds. `-1`: Disabled (default). |
## Manual Control Loss Failsafe
@ -283,7 +283,7 @@ Acting on a detected failure during flight is deactivated by default (enable by
During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions).
Note that this check is _always enabled on takeoff_, irrespective of the `CBRK_FLIGHTTERM` parameter.
The failure detector is active in all vehicle types and modes, except for those where the vehicle is _expected_ to do flips (i.e. [Acro mode (MC)](../flight_modes_mc/altitude.md), [Acro mode (FW)](../flight_modes_fw/altitude.md), and [Manual (FW)](../flight_modes_fw/manual.md)).
The failure detector is active in all vehicle types and modes, except for those where the vehicle is _expected_ to do flips (i.e. [Acro mode (MC)](../flight_modes_mc/acro.md), [Acro mode (FW)](../flight_modes_fw/acro.md), and [Manual (FW)](../flight_modes_fw/manual.md)).
### Attitude Trigger

View File

@ -34,7 +34,7 @@ If you update an existing file you are not required to make the whole file compl
### Line Length
- Maximum line length is 120 characters.
- Maximum line length is 140 characters.
### File Extensions

View File

@ -25,6 +25,7 @@ The boards in this category are:
- [CubePilot Cube Orange+](../flight_controller/cubepilot_cube_orangeplus.md)
- [CubePilot Cube Orange](../flight_controller/cubepilot_cube_orange.md)
- [CubePilot Cube Yellow](../flight_controller/cubepilot_cube_yellow.md)
- [Gear Up AirBrainH743](../flight_controller/gearup_airbrainh743.md)
- [Holybro Kakute H7v2](../flight_controller/kakuteh7v2.md)
- [Holybro Kakute H7mini](../flight_controller/kakuteh7mini.md)
- [Holybro Kakute H7](../flight_controller/kakuteh7.md)

View File

@ -0,0 +1,96 @@
# Gear Up AirBrainH743
:::warning
PX4 does not manufacture this (or any) autopilot.
Contact the [manufacturer](https://takeyourgear.com/) for hardware support.
:::
::: info
This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md).
:::
Purchase from [takeyourgear.com](https://takeyourgear.com/pages/products/airbrain).
For more information and pinout, check the [GitHub documentation](https://github.com/GearUp-Company/AirBrainH743).
## Key Features
- MCU: STM32H743 32-bit processor running at 480 MHz
- IMU: ICM42688P
- Barometer: DPS310
- Magnetometer: LIS2MDL (internal)
- 128MB NAND Flash for logging (W25N)
- 7x UARTs
- I2C, SPI
- 9x PWM Outputs (8 Motor outputs, 1 LED strip)
- Battery input voltage: 3S-10S
- Battery voltage/current monitoring
- 5V@2A and 10V@2.5A BEC outputs
- USB Type-C (IP68)
- EMC and ESD protection
## Connectors and Pins
:::warning
The pin order is different from the Pixhawk standard (compatible to the Betaflight standard).
:::
### UARTs
Current UART configuration:
| UART | Device | Function |
| ------ | ---------- | ---------------------------- |
| USART1 | /dev/ttyS0 | Console/Debug |
| USART2 | /dev/ttyS1 | RC Input |
| USART3 | /dev/ttyS2 | TEL4 (DJI/MSP) |
| UART4 | /dev/ttyS3 | TEL1 |
| UART5 | /dev/ttyS4 | TEL2 |
| UART7 | /dev/ttyS5 | TEL3 (ESC Telemetry) |
| UART8 | /dev/ttyS6 | GPS1 |
### Motor/Servo Outputs
| Connector | Pin | Function |
| ----------| ------------------ |
| ESC | M1 | Motor 1 |
| ESC | M2 | Motor 2 |
| ESC | M3 | Motor 3 |
| ESC | M4 | Motor 4 |
| PWM | M5 | Motor 5 |
| PWM | M6 | Motor 6 |
| PWM | M7 | Motor 7 |
| PWM | M8 | Motor 8 |
| AUX | M9 | LED/PWM/etc. |
<a id="bootloader"></a>
## PX4 Bootloader Update
Before PX4 firmware can be installed, the _PX4 bootloader_ must be flashed.
Download the [gearup_airbrainh743_bootloader.bin](https://github.com/PX4/PX4-Autopilot/blob/main/boards/gearup/airbrainh743/extras/gearup_airbrainh743_bootloader.bin) bootloader binary and read [this page](../advanced_config/bootloader_update_from_betaflight.md) for flashing instructions.
## Building Firmware
To [build PX4](../dev_setup/building_px4.md) for this target:
```
make gearup_airbrainh743_default
```
## Installing PX4 Firmware
Firmware can be installed in any of the normal ways:
- Build and upload the source:
```
make gearup_airbrainh743_default upload
```
- [Load the firmware](../config/firmware.md) using _QGroundControl_.
You can use either pre-built firmware or your own custom firmware.
### System Console
UART1 (ttyS0) is configured for use as the [System Console](../debug/system_console.md).

View File

@ -324,7 +324,7 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi
- [UXRCE_DDS_NS_IDX](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" />: Index-based namespace definition.
Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc.
See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces.
- [`UXRCE_DDS_FLCTRL`](../advanced_config/parameter_reference.md#UXRCE_DDS_FLCTRL) <Badge type="tip" text="PX4 main" />: Serial port hardware flow control enable.
- [`UXRCE_DDS_FLCTRL`](../advanced_config/parameter_reference.md#UXRCE_DDS_FLCTRL) <Badge type="tip" text="main (planned for: PX4 v1.18)" />: Serial port hardware flow control enable.
To use hardware flow control, a custom MicroXRCE Agent needs to be adopted. Please refer to [this PR](https://github.com/eProsima/Micro-XRCE-DDS-Agent/pull/407) for the required changes, cherry-pick them on top of the [agent version](#build-run-within-ros-2-workspace) you need to use and then run the agent with the additional `--flow-control` option.
::: info

View File

@ -88,13 +88,17 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too
```
:::tip
The main function must be named `<module_name>_main` and exported from the module as shown.
:::
:::tip
`PX4_INFO` is the equivalent of `printf` for the PX4 shell (included from **px4_platform_common/log.h**).
There are different log levels: `PX4_INFO`, `PX4_WARN`, `PX4_ERR`, `PX4_DEBUG`.
Warnings and errors are additionally added to the [ULog](../dev_log/ulog_file_format.md) and shown on [Flight Review](https://logs.px4.io/).
:::
1. Create and open a new _cmake_ definition file named **CMakeLists.txt**.
@ -160,7 +164,7 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too
1. Create and open a new _Kconfig_ definition file named **Kconfig** and define your symbol for naming (see [Kconfig naming convention](../hardware/porting_guide_config.md#px4-kconfig-symbol-naming-convention)).
Copy in the text below:
```
```text
menuconfig EXAMPLES_PX4_SIMPLE_APP
bool "px4_simple_app"
default n

View File

@ -22,7 +22,11 @@ If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tu
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
::: tip
For more information, see the Masters thesis from which this module was created: [Deep Reinforcement Learning for Embedded Control Policies for Aerial Vehicles](https://nva.sikt.no/registration/019b26689144-efeebae8-84d6-4413-ad7f-9aceb4ff7374).
In addition, the (Norwegian) website [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/) has a youtube video and a workshop paper .
:::
## Neural Network PX4 Firmware

View File

@ -35,7 +35,7 @@ The method we developed for training the RAPTOR policy is called Meta-Imitation
You can torture test the RAPTOR policy in your browser at [https://raptor.rl.tools](https://raptor.rl.tools) or in the embedded app here:
<iframe src="https://rl-tools.github.io/raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
<iframe src="https://raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
For more information please refer to the paper at [https://arxiv.org/abs/2509.11481](https://arxiv.org/abs/2509.11481).

View File

@ -11,7 +11,7 @@ PX4 traffic avoidance works with ADS-B or FLARM products that supply transponder
It has been tested with the following devices:
- [PingRX ADS-B Receiver](https://uavionix.com/product/pingrx-pro/) (uAvionix)
- [FLARM](https://flarm.com/products/uav/atom-uav-flarm-for-drones/) <!-- I think originally https://flarm.com/products/powerflarm/uav/ -->
- [FLARM](https://www.flarm.com/en/drones/)
## Hardware Setup

View File

@ -13,7 +13,7 @@ At the time of writing, parts of the PX4 ROS 2 Control Interface are experimenta
:::
The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ library that simplifies controlling PX4 from ROS 2.
The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ library (with Python bindings) that simplifies controlling PX4 from ROS 2.
Developers use the library to create and dynamically register modes written using ROS 2.
These modes are dynamically registered with PX4, and appear to be part of PX4 to a ground station or other external system.
@ -25,6 +25,12 @@ These classes abstract the internal setpoints used by PX4, and that can therefor
PX4 ROS 2 modes are easier to implement and maintain than PX4 internal modes, and provide more resources for developers in terms of processing power and pre-existing libraries.
Unless the mode is safety-critical, requires strict timing or very high update rates, or your vehicle doesn't have a companion computer, you should [consider using PX4 ROS 2 modes in preference to PX4 internal modes](../concept/flight_modes.md#internal-vs-external-modes).
::: tip
If you want to use Python, check out the [examples in the repository](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/python).
Not all classes have Python bindings yet — the [supported bindings are here](https://auterion.github.io/px4-ros2-interface-lib/python/index.html).
You are welcome to add and contribute missing classes.
:::
## Overview
This diagram provides a conceptual overview of how the control interface modes and mode executors interact with PX4.

View File

@ -6,7 +6,7 @@
At the time of writing, parts of the PX4 ROS 2 Interface Library are experimental, and hence subject to change.
:::
The [PX4 ROS 2 Interface Library](https://github.com/Auterion/px4-ros2-interface-lib) is a C++ library that simplifies controlling and interacting with PX4 from ROS 2.
The [PX4 ROS 2 Interface Library](https://github.com/Auterion/px4-ros2-interface-lib) is a C++ library (with Python bindings) that simplifies controlling and interacting with PX4 from ROS 2.
The library provides three high-level interfaces for developers:

View File

@ -15,6 +15,8 @@ The following models are supported by PX4, and can be connected to either the I2
| [LW20/C](https://lightware.co.za/products/lw20-c-100-m) | 100 | I2C bus | Waterproofed (IP67) with servo for sense-and-avoid applications |
| [SF30/D](https://lightwarelidar.com/shop/sf30-d-200-m/) | 200 | I2C bus | Waterproofed (IP67) |
| [SF45/B](../sensor/sf45_rotating_lidar.md) | 50 | Serial | Rotary Lidar (Used for [Collision Prevention](../computer_vision/collision_prevention.md)) |
| [GRF250](https://lightwarelidar.com/shop/grf-250/) | 250 | I2C | Gimbal Range Finder
| [GRF500](https://lightwarelidar.com/shop/grf-500/) | 500 | I2C | Gimbal Range Finder
::: details Discontinued

View File

@ -128,6 +128,7 @@
- [LED 신호 정의](getting_started/led_meanings.md)
- [알람 소리 정의](getting_started/tunes.md)
- [QGroundControl Flight-Readiness Status](flying/pre_flight_checks.md)
- [Asset Tracking](debug/asset_tracking.md)
- [Hardware Selection & Setup](hardware/drone_parts.md)
- [비행 컨트롤러 (오토파일럿)](flight_controller/index.md)
@ -273,6 +274,8 @@
- [Holybro M8N & M9N GPS](gps_compass/gps_holybro_m8n_m9n.md)
- [Sky-Drones SmartAP GPS](gps_compass/gps_smartap.md)
- [RTK GNSS](gps_compass/rtk_gps.md)
- [ARK G5 RTK GPS](dronecan/ark_g5_rtk_gps.md)
- [ARK G5 RTK HEADING GPS](dronecan/ark_g5_rtk_heading_gps.md)
- [ARK RTK GPS (CAN)](dronecan/ark_rtk_gps.md)
- [ARK RTK GPS L1 L5 (CAN)](dronecan/ark_rtk_gps_l1_l2.md)
- [ARK X20 RTK GPS (CAN)](dronecan/ark_x20_rtk_gps.md)
@ -840,9 +843,11 @@
- [Camera Integration/Architecture](camera/camera_architecture.md)
- [컴퓨터 비전](advanced/computer_vision.md)
- [Motion Capture (VICON, Optitrack, NOKOV)](tutorials/motion-capture.md)
- [Neural Networks](advanced/neural_networks.md)
- [Neural Network Module Utilities](advanced/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](advanced/tflm.md)
- [Neural Networks](neural_networks/index.md)
- [MC NN Control Module (Generic)](neural_networks/mc_neural_network_control.md)
- [Neural Network Module Utilities](neural_networks/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](neural_networks/tflm.md)
- [RAPTOR Adaptive RL NN Module](neural_networks/raptor.md)
- [Intel RealSense R200용 드라이버 설치](advanced/realsense_intel_driver.md)
- [상태 추정기 전환](advanced/switching_state_estimators.md)
- [트리 외부 모듈](advanced/out_of_tree_modules.md)
@ -925,6 +930,7 @@
- [출시](releases/index.md)
- [main (alpha)](releases/main.md)
- [1.17 (alpha)](releases/1.17.md)
- [1.16 (stable)](releases/1.16.md)
- [1.15](releases/1.15.md)
- [1.14](releases/1.14.md)

View File

@ -74,7 +74,7 @@ For example, you might have the following settings to assign the gimbal roll, pi
![Gimbal Actuator config](../../assets/config/actuators/qgc_actuators_gimbal.png)
The PWM values to use for the disarmed, maximum and minimum values can be determined in the same way as other servo, using the [Actuator Test sliders](../config/actuators.md#actuator-testing) to confirm that each slider moves the appropriate axis, and changing the values so that the gimbal is in the appropriate position at the disarmed, low and high position in the slider.
The PWM values to use for the disarmed, maximum, center and minimum values can be determined in the same way as other servo, using the [Actuator Test sliders](../config/actuators.md#actuator-testing) to confirm that each slider moves the appropriate axis, and changing the values so that the gimbal is in the appropriate position at the disarmed, low, center and high position in the slider.
The values may also be provided in gimbal documentation.
## Gimbal Control in Missions

View File

@ -1,119 +1 @@
# Neural Networks
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4.
It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on.
The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md) module.
The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame.
While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle.
Note that after training the network you will need to update and rebuild PX4.
TLFM is a mature inference library intended for use on embedded devices.
It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use.
If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview).
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
## Neural Network PX4 Firmware
:::warning
This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04).
:::
The module has been tested on a number of configurations, which can be build locally using the commands:
```sh
make px4_sitl_neural
```
```sh
make px4_fmu-v6c_neural
```
```sh
make mro_pixracerpro_neural
```
You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines:
```sh
CONFIG_LIB_TFLM=y
CONFIG_MODULES_MC_NN_CONTROL=y
```
:::tip
The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV.
:::
## Example Module Overview
The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below:
![neural_control](../../assets/advanced/neural_control.png)
In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow.
We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow.
We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md)
### Input
The input can be changed to whatever you want.
Set up the input you want to use during training and then provide the same input in PX4.
In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order:
- [3] Local position error. (goal position - current position)
- [6] The first 2 rows of a 3 dimensional rotation matrix.
- [3] Linear velocity
- [3] Angular velocity
All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function.
PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation.
Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one.
![ENU-NED](../../assets/advanced/ENU-NED.png)
ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure.
### 출력
The output consists of 4 values, the motor forces, one for each motor.
These are transformed in the `RescaleActions()` function.
This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values.
So the output from the network needs to be normalized before they can be sent to the motors in PX4.
The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic.
The publishing is handled in `PublishOutput(float* command_actions)` function.
:::tip
If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned.
Decrease it for more thrust.
:::
## Training your own Network
The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md).
But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended.
Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU.
If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/).
You should do one system identification flight for this and get an approximate inertia matrix for your platform.
On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md).
Then do the following steps:
- Do a hover flight
- Read of the logs what RPM is required for the drone to hover.
- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform.
- Insert these values into the Aerial Gym configuration and train your network.
- Convert the network as explained in [TFLM](tflm.md).
<Redirect to="../neural_networks/mc_neural_network_control" />

View File

@ -10,6 +10,10 @@ CAN it is designed to be democratic and uses differential signaling.
For this reason it is very robust even over longer cable lengths (on large vehicles), and avoids a single point of failure.
CAN also allows status feedback from peripherals and convenient firmware upgrades over the bus.
PX4 has the ability to track and log detailed information from CAN devices, including firmware versions, hardware versions, and serial numbers.
This enables unique identification and lifecycle tracking of hardware connected to the flight controller.
See [Asset Tracking](../debug/asset_tracking.md) for more information.
PX4 supports two software protocols for communicating with CAN devices:
- [DroneCAN](../dronecan/index.md): PX4 recommends this for most common setups.

View File

@ -106,7 +106,7 @@ There are several other "battery related" failsafe mechanisms that may be config
| 설정 | 매개변수 | 설명 |
| -------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None, `1`: Warning, `3`: Return mode (default). |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None (default), `1`: Warning, `3`: Return mode. |
| <a id="COM_FLT_TIME_MAX"></a> Maximum flight time failsafe level | [COM_FLT_TIME_MAX](../advanced_config/parameter_reference.md#COM_FLT_TIME_MAX) | Maximum allowed flight time before Return mode will be engaged, in seconds. `-1`: Disabled (default). |
## Manual Control Loss Failsafe
@ -121,36 +121,32 @@ PX4 and the receiver may also need to be configured in order to _detect RC loss_
![Safety - RC Loss (QGC)](../../assets/qgc/setup/safety/safety_rc_loss.png)
The QGCroundControl Safety UI allows you to set the [failsafe action](#failsafe-actions) and [RC Loss timeout](#COM_RC_LOSS_T).
Users that want to disable the RC loss failsafe in specific automatic modes (mission, hold, offboard) can do so using the parameter [COM_RCL_EXCEPT](#COM_RCL_EXCEPT).
The QGCroundControl Safety UI allows you to set the [failsafe action](#failsafe-actions) and [manual control loss timeout](#COM_RC_LOSS_T).
Users that want to disable this failsafe in specific modes can do so using the parameter [COM_RCL_EXCEPT](#COM_RCL_EXCEPT).
Additional (and underlying) parameter settings are shown below.
| 매개변수 | 설정 | 설명 |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_RC_LOSS_T"></a>[COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Manual Control Loss Timeout | Time after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the old manual control setpoint until the timeout triggers. |
| <a id="COM_RC_LOSS_T"></a>[COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Manual Control Loss Timeout | Time after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the last known stick position until the timeout triggers. |
| <a id="COM_FAIL_ACT_T"></a>[COM_FAIL_ACT_T](../advanced_config/parameter_reference.md#COM_FAIL_ACT_T) | Failsafe Reaction Delay | Delay in seconds between failsafe condition being triggered (`COM_RC_LOSS_T`) and failsafe action (RTL, Land, Hold). In this state the vehicle waits in hold mode for the manual control source to reconnect. This might be set longer for long-range flights so that intermittent connection loss doesn't immediately invoke the failsafe. It can be to zero so that the failsafe triggers immediately. |
| <a id="NAV_RCL_ACT"></a>[NAV_RCL_ACT](../advanced_config/parameter_reference.md#NAV_RCL_ACT) | 안전장치 동작 | Disabled, Loiter, Return, Land, Disarm, Terminate. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC 손실 예외 | Set the modes in which manual control loss is ignored: Mission, Hold, Offboard. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC 손실 예외 | Set modes in which manual control loss is ignored. |
## 데이터 연결불량 안전장치
The Data Link Loss failsafe is triggered if a telemetry link (connection to ground station) is lost.
The Data Link Loss failsafe is triggered if the connection to the last MAVLink ground station like QGroundControl is lost.
Users that want to disable this failsafe in specific modes can do so using the parameter [COM_DLL_EXCEPT](#COM_DLL_EXCEPT).
![Safety - Data Link Loss (QGC)](../../assets/qgc/setup/safety/safety_data_link_loss.png)
설정에 관련된 기본 매개변수는 다음과 같습니다.
| 설정 | 매개변수 | 설명 |
| -------------- | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------- |
| 데이터 연결불량 시간 초과 | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | 데이터 연결이 끊어진 후 안전 장치가 동작하기 전까지의 시간입니다. |
| 안전장치 동작 | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. |
다음 설정도 가능하지만 QGC UI에 표시되지 않습니다.
| 설정 | 매개변수 | 설명 |
| ----------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- |
| <a id="COM_DLL_EXCEPT"></a>Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes where DL loss will not trigger a failsafe. |
| 설정 | 매개변수 | 설명 |
| ----------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------- |
| 데이터 연결불량 시간 초과 | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | 데이터 연결이 끊어진 후 안전 장치가 동작하기 전까지의 시간입니다. |
| 안전장치 동작 | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. |
| <a id="COM_DLL_EXCEPT"></a>Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes in which data link loss is ignored. |
## Geofence 안전장치

View File

@ -0,0 +1,68 @@
# Asset Tracking
<Badge type="tip" text="main (planned for: PX4 v1.18)" />
PX4 can track and log detailed information about external hardware devices connected to the flight controller.
This enables unique identification of vehicle parts throughout their operational lifetime using device IDs, serial numbers, and version information.
:::info
Asset tracking is currently implemented for [DroneCAN](../dronecan/index.md) devices only.
:::
## 개요
Asset tracking allows you to determine exactly which hardware is installed on a vehicle, providing serial number, version, and other information.
This makes it easier to track and maintain specific vehicle parts across multiple vehicles, to quickly see what versions you're running when debugging, and log component information for regulatory audits.
Asset tracking automatically collects and logs the following metadata from external devices:
- **Device identification**: Vendor name, model name, device type
- **Version information**: Firmware version, hardware version
- **Unique identifiers**: Serial number, device ID
- **Device capabilities**: ESC, GPS, magnetometer, barometer, etc.
This information is published via the [`device_information`](../msg_docs/DeviceInformation.md) uORB topic and logged to flight logs.
This enables fleet management, maintenance tracking, and troubleshooting.
## Viewing Device Information
### Real-Time Monitoring
You can view device information in real-time using the [MAVLink Shell](../debug/mavlink_shell.md) or console:
```sh
listener device_information
```
Example output for a CAN GPS module:
```plain
TOPIC: device_information
device_information
timestamp: 16258961403 (0.216525 seconds ago)
device_id: 8944643 (Type: 0x88, UAVCAN:0 (0x7C))
device_type: 5
vendor_name: "cubepilot"
model_name: "here4"
firmware_version: "1.14.3006590"
hardware_version: "4.19"
serial_number: "1c00410018513331"
```
Device information is published in a round-robin fashion for each detected device, at a rate of approximately 1 Hz.
### Multi-Capability Devices
Devices with multiple sensors (e.g., a CAN GPS/magnetometer combo module like the HERE4) register separate device information entries for each capability.
Each entry shares the same serial number and base metadata but has a different `device_id` corresponding to the specific sensor capability.
## 비행 로그 분석
Device information is automatically logged to flight logs.
You can extract it using [pyulog](../log/flight_log_analysis.md#pyulog), though note that fields like vendor name, model name, and serial number are stored as `char` arrays and require additional parsing.
## See Also
- [CAN (DroneCAN & Cyphal)](../can/index.md) — CAN bus configuration and setup
- [DroneCAN](../dronecan/index.md) — DroneCAN-specific documentation
- [Flight Log Analysis](../log/flight_log_analysis.md) — Flight log analysis

View File

@ -0,0 +1,112 @@
# ARK G5 RTK GPS
:::info
This GPS module is made in the USA and NDAA compliant.
:::
[ARK G5 RTK GPS](https://arkelectron.com/product/ark-g5-rtk-gps/) is a [DroneCAN](index.md) quad-band [RTK GPS](../gps_compass/rtk_gps.md).
The module incorporates the [Septentrio mosaic-G5 P3 Ultra-compact high-precision GPS/GNSS receiver module](https://www.u-blox.com/en/product/zed-x20p-module), magnetometer, barometer, IMU, and buzzer module.
![ARK G5 RTK GPS](../../assets/hardware/gps/ark/ark_g5_rtk_gps.png)
## 구매처
Order this module from:
- [ARK Electronics](https://arkelectron.com/product/ark-g5-rtk-gps/) (US)
## Hardware Specifications
- [DroneCAN](index.md) RTK GNSS, Magnetometer, Barometer, IMU, and Buzzer Module
- [Dronecan Firmware Updating](../dronecan/index.md#firmware-update)
- 센서
- [Septentrio mosaic-G5 P3 Ultra-compact high-precision GPS/GNSS receiver module](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3)
- All-band all constellation GNSS receiver
- All-in-view satellite tracking: multi-constellation, quad-band GNSS module receiver
- Full raw data with positioning measurements and Galileo HAS positioning service compatibility
- Best-in-class RTK cm-level positioning accuracy
- Advanced GNSS+ algorithms
- 20Hz update rate
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
- [Bosch BMP390 Barometer](https://www.bosch-sensortec.com/products/environmental-sensors/pressure-sensors/bmp390/)
- [Invensense ICM-42688-P 6-Axis IMU](https://invensense.tdk.com/products/motion-tracking/6-axis/icm-42688-p/)
- STM32F412VGH6 MCU
- Safety Button
- 부저
- Two CAN Connectors (Pixhawk Connector Standard 4-pin JST GH)
- G5 "UART 2" Connector
- 4-pin JST GH
- TX, RX, PPS, GND
- G5 USB C
- Debug Connector (Pixhawk Connector Standard 6-pin JST SH)
- LED Indicators
- GPS Fix
- RTK Status
- RGB system status
- USA Built
- NDAA Compliant
- Power Requirements
- 5V
- 270mA
- 크기
- Without Antenna
- 48.0mm x 40.0mm x 15.4mm
- 13.0g
- With Antenna
- 48.0mm x 40.0mm x 51.0mm
- 43.5g
- Includes
- CAN Cable (Pixhawk Connector Standard 4-pin)
- Full-Frequency Helical GPS Antenna
## 하드웨어 설정
### 배선
The ARK G5 RTK GPS is connected to the CAN bus using a [Pixhawk connector standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) 4-pin JST GH cable.
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
### 장착
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 Configuration](#px4-configuration).
## Firmware Setup
The Septentrio G5 module firmware can be updated using the Septentrio [RxTools](https://www.septentrio.com/en/products/gps-gnss-receiver-software/rxtools) application.
## Flight Controller Setup
### Enabling DroneCAN
In order to use the ARK G5 RTK GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
단계는 다음과 같습니다:
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
- Connect ARK G5 RTK GPS CAN to the Pixhawk CAN.
Once enabled, the module will be detected on boot.
There is also CAN built-in bus termination via [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM)
### PX4 설정
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK G5 RTK GPS from the vehicle's centre of gravity.
## LED 신호의 의미
The GPS status lights are located to the right of the connectors:
- Blinking green is GPS fix
- Blinking blue is received corrections and RTK Float
- Solid blue is RTK Fixed
## See Also
- [ARK G5 RTK GPS Documentation](https://docs.arkelectron.com/gps/ark-g5-rtk-gps) (ARK Docs)

View File

@ -0,0 +1,150 @@
# ARK G5 RTK HEADING GPS
:::info
This GPS module is made in the USA and NDAA compliant.
:::
[ARK G5 RTK HEADING GPS](https://arkelectron.com/product/ark-g5-rtk-gps/) is a [DroneCAN](index.md) quad-band dual antenna [RTK GPS](../gps_compass/rtk_gps.md) that additionally provides vehicle yaw information from GPS.
The module incorporates the [Septentrio mosaic-G5 P3H Ultra-compact high-precision GPS/GNSS receiver module with heading capability](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H), magnetometer, barometer, IMU, and buzzer module.
![ARK G5 RTK HEADING GPS](../../assets/hardware/gps/ark/ark_g5_rtk_gps.png)
## 구매처
Order this module from:
- [ARK Electronics](https://arkelectron.com/product/ark-g5-rtk-heading-gps/) (US)
## Hardware Specifications
- [DroneCAN](index.md) RTK GNSS, Magnetometer, Barometer, IMU, and Buzzer Module
- [Dronecan Firmware Updating](../dronecan/index.md#firmware-update)
- 센서
- [Septentrio mosaic-G5 P3H Ultra-compact high-precision GPS/GNSS receiver module with heading capability](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H)
- All-band all constellation GNSS receiver
- All-in-view satellite tracking: multi-constellation, quad-band GNSS module receiver
- Full raw data with positioning measurements and Galileo HAS positioning service compatibility
- Best-in-class RTK cm-level positioning accuracy
- Advanced GNSS+ algorithms
- 20Hz update rate
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
- [Bosch BMP390 Barometer](https://www.bosch-sensortec.com/products/environmental-sensors/pressure-sensors/bmp390/)
- [Invensense ICM-42688-P 6-Axis IMU](https://invensense.tdk.com/products/motion-tracking/6-axis/icm-42688-p/)
- STM32F412VGH6 MCU
- Safety Button
- 부저
- Two CAN Connectors (Pixhawk Connector Standard 4-pin JST GH)
- G5 "UART 2" Connector
- 4-pin JST GH
- TX, RX, PPS, GND
- G5 USB C
- Debug Connector (Pixhawk Connector Standard 6-pin JST SH)
- LED Indicators
- GPS Fix
- RTK Status
- RGB system status
- USA Built
- NDAA Compliant
- Power Requirements
- 5V
- 270mA
- 크기
- Without Antenna
- 48.0mm x 40.0mm x 15.4mm
- 13.0g
- With Antenna
- 48.0mm x 40.0mm x 51.0mm
- 43.5g
- Includes
- CAN Cable (Pixhawk Connector Standard 4-pin)
- Full-Frequency Helical GPS Antenna
## 하드웨어 설정
### 배선
The ARK G5 RTK HEADING GPS is connected to the CAN bus using a [Pixhawk connector standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) 4-pin JST GH cable.
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
### 장착
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 configuration](#px4-configuration).
## Firmware Setup
The Septentrio G5 module firmware can be updated using the Septentrio [RxTools](https://www.septentrio.com/en/products/gps-gnss-receiver-software/rxtools) application.
## Flight Controller Setup
### Enabling DroneCAN
In order to use the ARK G5 RTK HEADING GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
단계는 다음과 같습니다:
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
- Connect ARK G5 RTK HEADING GPS CAN to the Pixhawk CAN.
Once enabled, the module will be detected on boot.
There is also CAN built-in bus termination via [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM)
### PX4 설정
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK G5 RTK HEADING GPS from the vehicle's centre of gravity.
### Parameter references
This GPS is using ARK's private driver, the prameters below only exist on the firmware we ship the GPS with. You can set these params either in QGC or using the DroneCAN GUI Tool.
#### SEP_OFFS_YAW (float)
Heading offset angle for dual antenna GPS setups that support heading estimation.
Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the Rover/ANT2 antenna is in front.
The offset angle increases clockwise.
Set this to 90 if the ANT2 antenna is placed on the right side of the vehicle and the Moving Base/MAIN antenna is on the left side.
- Default: 0
- Min: -360
- Max: 360
- Unit: degree
#### SEP_OFFS_PITCH (float)
Vertical offsets can be compensated for by adjusting the Pitch offset.
Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. Since pitch is defined as the right-handed rotation about the vehicle Y axis, a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch.
- Default: 0
- Min: -90
- Max: 90
- Unit: degree
#### SEP_OUT_RATE (enum)
Configures the output rate for GNSS data messages.
- -1: OnChange (Default)
- 50: 50 ms
- 100: 100 ms
- 200: 200 ms
- 500: 500 ms
## LED 신호의 의미
The GPS status lights are located to the right of the connectors:
- Blinking green is GPS fix
- Blinking blue is received corrections and RTK Float
- Solid blue is RTK Fixed
## See Also
- [ARK G5 RTK HEADING GPS Documentation](https://docs.arkelectron.com/gps/ark-g5-rtk-gps) (ARK Docs)

View File

@ -27,6 +27,8 @@ Connecting peripherals over DroneCAN has many benefits:
- Wiring is less complicated as you can have a single bus for connecting all your ESCs and other DroneCAN peripherals.
- Setup is easier as you configure ESC numbering by manually spinning each motor.
- It allows users to configure and update the firmware of all CAN-connected devices centrally through PX4.
- PX4 automatically tracks device information (vendor, model, versions, serial numbers) for maintenance and fleet management.
See [Asset Tracking](../debug/asset_tracking.md).
## 지원 하드웨어

View File

@ -1,6 +1,6 @@
# Gain compression
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
Automatic gain compression reduces the gains of the angular-rate PID whenever oscillations are detected.
It monitors the angular-rate controller output through a band-pass filter to identify these oscillations.

View File

@ -1,6 +1,6 @@
# MicoAir743-Lite
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
:::warning
PX4 does not manufacture this (or any) autopilot.

View File

@ -1,6 +1,6 @@
# RadiolinkPIX6 Flight Controller
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
:::warning
PX4 does not manufacture this (or any) autopilot.

View File

@ -1,6 +1,6 @@
# AP-H743-R1
# AP-H743-R1 Flight Controller
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
:::warning
PX4 does not manufacture this (or any) autopilot.
@ -25,7 +25,7 @@ It brings you ultimate performance, stability, and reliability in every aspect.
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- 내장 센서 :
- Accel/Gyro: ICM-42688-P\*2(Version1), BMI270\*2(Version2)
- 자력계: QMC5883P
- Mag: QMC5883P
- Barometer: DPS310(Version1),SPL06(Version2)
### 인터페이스

View File

@ -2,11 +2,14 @@
<img src="../../assets/site/position_fixed.svg" title="Position fix required (e.g. GPS)" width="30px" />
The _Hold_ flight mode causes the vehicle to loiter (circle) around its current GPS position and maintain its current altitude.
The _Hold_ flight mode causes the vehicle to loiter around its current GPS position and maintain its current altitude.
The mode supports a [number of distinct loiter modes](#loiter-modes), which are triggered using different QGC controls or MAVLink commands.
These allow loitering with circular and figure 8 flight paths.
:::tip
_Hold mode_ can be used to pause a mission or to help you regain control of a vehicle in an emergency.
It is usually activated with a pre-programmed switch.
It is usually activated with a pre-programmed RC switch.
:::
::: info
@ -24,24 +27,80 @@ It is usually activated with a pre-programmed switch.
:::
## Technical Summary
## Loiter modes
The aircraft circles around the GPS hold position at the current altitude.
The vehicle will first ascend to [NAV_MIN_LTR_ALT](#NAV_MIN_LTR_ALT) if the mode is engaged below this altitude.
### Default Loiter
RC stick movement is ignored.
The aircraft circles around the position at which the mode was triggered and maintain its current altitude.
The loiter radius is set by the parameter [NAV_LOITER_RAD](#NAV_LOITER_RAD).
Note that if the vehicle altitude is below [NAV_MIN_LTR_ALT](#NAV_MIN_LTR_ALT), it will ascend to that minimum altitude before circling.
### 매개변수
The default loiter mode is entered when you switch to Hold mode without explicitly specifying any loiter behaviour.
For example, if you switch to Hold mode using an RC switch, select **Hold** on the QGC flight mode selector, or activate the mode using the MAVLink [MAV_CMD_DO_SET_MODE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_MODE) command.
### Orbit Loiter Mode
<Badge type="tip" text="PX4 v1.12" />
The aircraft travels towards a _specified_ orbit center position, then circles it with a given direction and radius.
This behaviour can be accessed in QGroundControl by clicking on the map in Fly view, selecting **Orbit at Location**, and configuring the radius.
The behavior can be triggered using the MAVLink [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) command.
Note that PX4 respects the specified centre point (`param5`, `param6`, `param7`), and the radius and direction (`param1`).
PX4 ignores `param3` (Yaw behaviour) and `param4` (Orbits).
The value of `param2` (velocity) is also ignored, but the speed can be controlled using the [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED) command (constrained between `FW_AIRSPD_MAX` and `FW_AIRSPD_MIN`).
PX4 outputs orbit status using the [ORBIT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#ORBIT_EXECUTION_STATUS) message.
### Figure 8 Loiter Mode
<Badge type="tip" text="PX4 v1.15" /> <Badge type="warning" text="Experimental" />
The aircraft flys towards the closest point on a specified figure 8 path and then follows it.
The path is defined by the figure 8 centre position, orientation, and radius of two circles.
The feature is experimental, and is not present in PX4 firmware by default (on most flight controller boards).
It can be included by setting the `CONFIG_FIGURE_OF_EIGHT` key in the [PX4 board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) for your board and rebuilding.
For example, this is enabled on the [default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/default.px4board#L46) file for the `auterion/fmu-v6s` board.
The behavior can be triggered using the MAVLink [MAV_CMD_DO_FIGURE_EIGHT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FIGURE_EIGHT) command (PX4 respects all the parameters).
PX4 outputs the figure 8 status using the [FIGURE_EIGHT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#FIGURE_EIGHT_EXECUTION_STATUS) message.
:::info
Figure 8 loitering is not currently supported by QGC: [QGC#12778: Need Support Figure of eight (8 figure) loitering by QGC](https://github.com/mavlink/qgroundcontrol/issues/12778).
:::
Figure 8 loitering is also available in the simulator.
You can test it in [Gazebo](../sim_gazebo_gz/index.md) using a fixed wing frame:
```sh
make px4_sitl gz_rc_cessna
```
## 매개변수
Hold mode behaviour can be configured using the parameters below.
| 매개변수 | 설명 |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------ |
| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The radius of the loiter circle. |
| <a id="NAV_LOITER_RAD"></a>[NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The radius of the loiter circle. |
| <a id="NAV_MIN_LTR_ALT"></a>[NAV_MIN_LTR_ALT](../advanced_config/parameter_reference.md#NAV_MIN_LTR_ALT) | Minimum height for loiter mode (vehicle will ascend to this altitude if mode is engaged at a lower altitude). |
## MAVLink Commands
The following commands are relevant to this mode:
- [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) - Switch to Hold mode and start the specified [Orbit loiter](#orbit-loiter-mode).
Params 2 (velocity), 3 (yaw), 4 (orbits) are ignored.
[ORBIT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#ORBIT_EXECUTION_STATUS) is emitted.
- [MAV_CMD_DO_FIGURE_EIGHT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FIGURE_EIGHT) - Switch to Hold mode and start the specified [Figure 8 loiter](#figure-8-loiter-mode).
All params are respected.
[FIGURE_EIGHT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#FIGURE_EIGHT_EXECUTION_STATUS) is emitted.
Note, other commands may be supported.
## See Also
[Hold Mode (MC)](../flight_modes_mc/hold.md)
- [Hold Mode (MC)](../flight_modes_mc/hold.md)
<!-- this maps to AUTO_LOITER in flight mode state machine -->

View File

@ -49,8 +49,8 @@ If the local position is invalid or becomes invalid while executing the takeoff,
::: info
- Takeoff towards a target position was added in <Badge type="tip" text="main (planned for: PX4 v1.17)" />.
- Holding wings level and ascending to clearance attitude when local position is invalid during takeoff was added in <Badge type="tip" text="main (planned for: PX4 v1.17)" />.
- Takeoff towards a target position was added in <Badge type="tip" text="PX4 v1.17" />.
- Holding wings level and ascending to clearance attitude when local position is invalid during takeoff was added in <Badge type="tip" text="PX4 v1.17" />.
- QGroundControl does not support `MAV_CMD_NAV_TAKEOFF` (at time of writing).
:::

View File

@ -21,52 +21,59 @@ PX4 supports the [u-blox M8P](https://www.u-blox.com/en/product/neo-m8p), [u-blo
The table indicates devices that also output yaw, and that can provide yaw when two on-vehicle units are used.
It also highlights devices that connect via the CAN bus, and those which support PPK (Post-Processing Kinematic).
| 장치 | GPS | 나침반 | [DroneCAN](../dronecan/index.md) | [GPS Yaw](#configuring-gps-as-yaw-heading-source) | PPK |
| :------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------: | :------: | :------------------------------: | :-----------------------------------------------: | :-: |
| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P][DualF9P] | |
| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | |
| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna][SeptDualAnt] | |
| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | BMP390 | ✓ | | |
| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | ✓ | | | |
| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | ✓ |
| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | |
| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | |
| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P](https://docs.datagnss.com/gnss/gnss_module/D10P_RTK) | IST8310 | | ✘ | |
| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | ✘ | |
| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | ✓ | | | |
| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | |
| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | ✓ | [Dual F9P][DualF9P] | |
| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P][DualF9P] | |
| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | ✓ | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | |
| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | |
| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna][UnicoreDualAnt] | |
| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | |
| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | |
| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | |
| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | |
| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | |
| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna][SeptDualAnt] | ✓ |
| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | [Septentrio Dual Antenna][SeptDualAnt] | ✓ |
| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | |
| 장치 | GPS | 나침반 | [DroneCAN] | [GPS Yaw] | PPK |
| :------------------------------------------------------------------------------------------------------------------- | :------------------: | :------: | :--------: | :---------------------------------: | :-: |
| [ARK G5 RTK GPS](../dronecan/ark_g5_rtk_gps.md) | [mosaic-G5 P3] | IIS2MDC | ✓ | | |
| [ARK G5 RTK HEADING GPS](../dronecan/ark_g5_rtk_heading_gps.md) | [mosaic-G5 P3H] | IIS2MDC | ✓ | [Heading Capability][mosaic-G5 P3H] | |
| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P] | |
| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | |
| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna] | |
| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | IIS2MDC | ✓ | | |
| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | ✓ | | | |
| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P] | |
| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P] | |
| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | ✓ |
| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | |
| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | |
| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P] | |
| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P] | IST8310 | | ✘ | |
| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | ✘ | |
| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | ✓ | | | |
| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | |
| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | ✓ | [Dual F9P] | |
| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P] | |
| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P] | |
| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P] | |
| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | ✓ | [Dual F9P] | |
| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | |
| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P] | |
| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | |
| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna] | |
| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | |
| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | |
| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | [Dual F9P] | |
| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | |
| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | |
| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | |
| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna] | ✓ |
| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | [Septentrio Dual Antenna] | ✓ |
| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P] | |
| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P] | |
| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | |
<!-- links used in above table -->
[RaccnLabL1L2ZED-F9P ext_ant]: https://docs.raccoonlab.co/guide/gps_mag_baro/gnss_external_antenna_f9p_v320.html
[RaccoonLab L1/L2 ZED-F9P]: https://docs.raccoonlab.co/guide/gps_mag_baro/gps_l1_l2_zed_f9p.html
[DualF9P]: ../gps_compass/u-blox_f9p_heading.md
[SeptDualAnt]: ../gps_compass/septentrio.md#gnss-based-heading
[UnicoreDualAnt]: ../gps_compass/rtk_gps_holybro_unicore_um982.md#enable-gps-heading-yaw
[Dual F9P]: ../gps_compass/u-blox_f9p_heading.md
[Septentrio Dual Antenna]: ../gps_compass/septentrio.md#gnss-based-heading
[Unicore Dual Antenna]: ../gps_compass/rtk_gps_holybro_unicore_um982.md#enable-gps-heading-yaw
[DATAGNSS GEM1305 RTK]: ../gps_compass/rtk_gps_gem1305.md
[DroneCAN]: ../dronecan/index.md
[GPS Yaw]: #configuring-gps-as-yaw-heading-source
[mosaic-G5 P3]: https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3
[mosaic-G5 P3H]: https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H
[D10P]: https://docs.datagnss.com/gnss/gnss_module/D10P_RTK
참고:
@ -146,6 +153,7 @@ RTK GPS 연결은 기본적으로 플러그앤플레이입니다.
![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png)
4. Survey-in이 완료되면 :
- The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle:
![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png)

View File

@ -332,9 +332,11 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi
- [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT): Bridge time synchronization enable.
The uXRCE-DDS client module can synchronize the timestamp of the messages exchanged over the bridge.
This is the default configuration. In certain situations, for example during [simulations](../ros2/user_guide.md#ros-gazebo-and-px4-time-synchronization), this feature may be disabled.
- <Badge type="tip" text="PX4 v1.17" /> [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX): Index-based namespace definition
- [UXRCE_DDS_NS_IDX](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" />: Index-based namespace definition.
Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc.
See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces.
- [`UXRCE_DDS_FLCTRL`](../advanced_config/parameter_reference.md#UXRCE_DDS_FLCTRL) <Badge type="tip" text="PX4 main" />: Serial port hardware flow control enable.
To use hardware flow control, a custom MicroXRCE Agent needs to be adopted. Please refer to [this PR](https://github.com/eProsima/Micro-XRCE-DDS-Agent/pull/407) for the required changes, cherry-pick them on top of the [agent version](#build-run-within-ros-2-workspace) you need to use and then run the agent with the additional `--flow-control` option.
:::info
Many ports are already have a default configuration.
@ -439,7 +441,7 @@ will generate topics under the namespaces:
:::
- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to a value between 0 and 9999.
- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" /> to a value between 0 and 9999.
This will generate a namespace such as `/uav_0`, `/uav_1`, and so on.
This technique is ideal if vehicles must be persistently associated with namespaces because their clients are automatically started through PX4.

View File

@ -0,0 +1,21 @@
# Neural Network Control
PX4 supports the following mechanisms for using neural networks for multirotor control:
- [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md)<Badge type="warning" text="Experimental" /> — A generic neural network module that you can modify to use different underlying neural network and training models and compile into the firmware.
- [RAPTOR: A Neural Network Module for Adaptive Quadrotor Control](../neural_networks/raptor.md)<Badge type="warning" text="Experimental" /> — An adaptive RL NN module that works well with different Quad configurations without additional training.
Generally you will select the former if you wish to experiment with custom neural network architectures and train them using PyTorch or TensorFlow, and the latter if you want to use a pre-trained neural-network controller that works out-of-the-box (without training for your particular platform) or if you train your own policies using [RLtools](https://rl.tools).
Note that both modules are experimental and provided for experimentation.
The table below provides more detail on the differences.
| Use Case | [`mc_raptor`](../neural_networks/raptor.md) | [`mc_nn_control`](../neural_networks/mc_neural_network_control.md) |
| ---------------------------------------------------------------- | ------------------------------------------- | ------------------------------------------------------------------ |
| Pre-trained policy that adapts to any quadrotor without training | ✓ RAPTOR | ✘ |
| Train policy in PyTorch/TF | ✘ | ✓ TF Lite |
| Train policy in RLtools | ✓ | ✘ |
| Use manual control (remote) with NN policy | ✘ GPS/MoCap | ✓ Manual attitude commands |
| Load policy checkpoints from SD card | ✓ Upload via MAVLink FTP | ✘ Compiled into firmware |
| Offboard setpoints | ✓ MAVLink | ✘ |
| Internal Trajectory Generator | ✓ (Position, Lissajous) | ✘ |

View File

@ -0,0 +1,119 @@
# MC Neural Networks Control
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4.
It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on.
The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](./tflm.md) module.
The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame.
While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle.
Note that after training the network you will need to update and rebuild PX4.
TLFM is a mature inference library intended for use on embedded devices.
It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use.
If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview).
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
## Neural Network PX4 Firmware
:::warning
This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04).
:::
The module has been tested on a number of configurations, which can be build locally using the commands:
```sh
make px4_sitl_neural
```
```sh
make px4_fmu-v6c_neural
```
```sh
make mro_pixracerpro_neural
```
You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines:
```sh
CONFIG_LIB_TFLM=y
CONFIG_MODULES_MC_NN_CONTROL=y
```
:::tip
The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV.
:::
## Example Module Overview
The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below:
![neural_control](../../assets/advanced/neural_control.png)
In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow.
We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow.
We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md)
### Input
The input can be changed to whatever you want.
Set up the input you want to use during training and then provide the same input in PX4.
In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order:
- [3] Local position error. (goal position - current position)
- [6] The first 2 rows of a 3 dimensional rotation matrix.
- [3] Linear velocity
- [3] Angular velocity
All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function.
PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation.
Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one.
![ENU-NED](../../assets/advanced/ENU-NED.png)
ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure.
### 출력
The output consists of 4 values, the motor forces, one for each motor.
These are transformed in the `RescaleActions()` function.
This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values.
So the output from the network needs to be normalized before they can be sent to the motors in PX4.
The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic.
The publishing is handled in `PublishOutput(float* command_actions)` function.
:::tip
If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned.
Decrease it for more thrust.
:::
## Training your own Network
The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md).
But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended.
Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU.
If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/).
You should do one system identification flight for this and get an approximate inertia matrix for your platform.
On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md).
Then do the following steps:
- Do a hover flight
- Read of the logs what RPM is required for the drone to hover.
- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform.
- Insert these values into the Aerial Gym configuration and train your network.
- Convert the network as explained in [TFLM](tflm.md).

View File

@ -0,0 +1,86 @@
# Neural Network Module: System Integration
The neural control module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) implements an end-to-end controller utilizing neural networks.
The parts of the module directly concerned with generating the code for the trained neural network and integrating it into the module are covered in [TensorFlow Lite Micro (TFLM)](./tflm.md).
This page covers the changes that were made to integrate the module into PX4, both within the module, and in larger system configuration.
:::tip
This topic should help you to shape the module to your own needs.
You will need some familiarity with PX4 development.
For more information see the developer [Getting Started](../dev_setup/getting_started.md).
:::
## 자동 실행
A line to autostart the [mc_nn_control](../modules/modules_controller.md#mc-nn-control) module has been added in the [`ROMFS/px4fmu_common/init.d/rc.mc_apps`](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/rc.mc_apps) startup script.
It checks whether the module is included by looking for the parameter [MC_NN_EN](../advanced_config/parameter_reference.md#MC_NN_EN).
If this is set to `1` (the default value), the module will be started when booting PX4.
Similarly you could create other parameters in the [`mc_nn_control_params.c`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/mc_nn_control_params.c) file for other startup script checks.
## Custom Flight Mode
The module creates its own flight mode "Neural Control" which lets you choose it from the flight mode menu in QGC and bind it to a switch on you RC controller.
This is done by using the [ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) internally.
This involves several steps and is visualized here:
:::info
The module does not actually use ROS 2, it just uses the API exposed through uORB topics.
:::
:::info
In some QGC versions the flight mode does not show up, so make sure to update to the newest version.
This only works for some flight controllers, so you might have to use an RC controller to switch to the correct external flight mode.
:::
![neural_mode_registration](../../assets/advanced/neural_mode_registration.png)
1. Publish a [RegisterExtComponentRequest](../msg_docs/RegisterExtComponentRequest.md).
This specifies what you want to create, you can read more about this in the [Control Interface](../ros2/px4_ros2_control_interface.md).
In this case we register an arming check and a mode.
2. Wait for a [RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md).
This will give feedback on wether the mode registration was successful, and what the mode and arming check id is for the new mode.
3. [Optional] With the mode id, publish a [VehicleControlMode](../msg_docs/VehicleControlMode.md) message on the `config_control_setpoints` topic.
Here you can configure what other modules run in parallel.
The example controller replaces everything, so it turns off allocation.
If you want to replace other parts you can enable or disable the modules accordingly.
4. [Optional] With the mode id, publish a [ConfigOverrides](../msg_docs/ConfigOverrides.md) on the `config_overrides_request` topic.
(This is not done in the example module) This will let you defer failsafes or stop it from automatically disarming.
5. When the mode has been registered a [ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) will be sent, asking if your mode has everything it needs to run.
This message must be answered with a [ArmingCheckReply](../msg_docs/ArmingCheckReply.md) so the mode is not flagged as unresponsive.
In this response it is possible to set what requirements the mode needs to run, like local position.
If any of these requirements are set the commander will stop you from switching to the mode if they are not fulfilled.
It is also important to set health_component_index and num_events to 0 to not get a segmentation fault.
Unless you have a health component or events.
6. Listen to the [VehicleStatus](../msg_docs/VehicleStatus.md) topic.
If the nav_state equals the assigned `mode_id`, then the Neural Controller is activated.
7. When active the module will run the controller and publish to [ActuatorMotors](../msg_docs/ActuatorMotors.md).
If you want to replace a different part of the controller, you should find the appropriate topic to publish to.
To see how the requests are handled you can check out [src/modules/commander/ModeManagement.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/commander/ModeManagement.cpp).
## 로깅
To add module-specific logging a new topic has been added to [uORB](../middleware/uorb.md) called [NeuralControl](../msg_docs/NeuralControl.md).
The message definition is also added in `msg/CMakeLists.txt`, and to [`src/modules/logger/logged_topics.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/logger/logged_topics.cpp) under the debug category.
For these messages to be saved in your logs you need to include `debug` in the [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) parameter.
## Timing
The module has two includes for measuring the inference times.
The first one is a driver that works on the actual flight controller units, but a second one, `chrono`, is loaded for SITL testing.
Which timing library is included and used is based on wether PX4 is built with NUTTX or not.
## Changing the setpoint
The module uses the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message's position fields to define its target.
To follow a trajectory, you can send updated setpoints.
For an example of how to do this in a PX4 module, see the [mc_nn_testing](https://github.com/SindreMHegre/PX4-Autopilot-public/tree/main/src/modules/mc_nn_testing) module in this fork.
Note that this is not included in upstream PX4.
To use it, copy the module folder from the linked repository into your workspace, and enable it by adding the following line to your `.px4board` file:
```sh
CONFIG_MODULES_MC_NN_TESTING=y
```

View File

@ -0,0 +1,221 @@
# RAPTOR: A Neural Network Module for Adaptive Quadrotor Control
<Badge type="tip" text="main (planned for PX4 v1.18)" /> <Badge type="info" text="Multicopter" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
RAPTOR is a tiny reinforcement-learning based neural network module for quadrotor control that can be used to control a wide variety of quadrotors without retuning.
This topic provides an overview of the fundamental concepts, and explains how you can use the module in simulation and real hardware.
## 개요
![Visual Abstract](../../assets/advanced/neural_networks/raptor/visual_abstract.jpg)
RAPTOR is an adaptive policy for end-to-end quadrotor control.
It is motivated by the human ability to adapt learned behaviours to similar situations.
For example, while humans may initially require many hours of driving experience to be able to smoothly control the car and blend into traffic, when faced with a new vehicle they do not need to re-learn how to drive — they only need to experience a few rough braking/acceleration/steering responses to adjust their previously learned behavior.
Reinforcement Learning (RL) is a machine learning technique that uses trial and error to learn decision making/control behaviors, which is similar to the way that humans learn to drive.
RL is interesting for controlling robots (and particularly UAVs) because it overcomes some fundamental limitations of classic, modular control architectures (information loss at module boundaries, requirement for expert tuning, etc).
RL has been very successful in [high-performance quadrotor flight](https://doi.org/10.1038/s41586-023-06419-4), but previous designs have not been particularly adaptable to new frames and vehicle types.
RAPTOR fills this gap and demonstrates a single, tiny neural-network control policy that can control a wide variety of quadrotors (tested on real quadrotors from 32 g to 2.4 kg).
For more details please refer to this video:
<lite-youtube videoid="hVzdWRFTX3k" title="RAPTOR: A Foundation Policy for Quadrotor Control"/>
The method we developed for training the RAPTOR policy is called Meta-Imitation Learning:
![Diagram showing the Method Overview](../../assets/advanced/neural_networks/raptor/method.jpg)
You can torture test the RAPTOR policy in your browser at [https://raptor.rl.tools](https://raptor.rl.tools) or in the embedded app here:
<iframe src="https://rl-tools.github.io/raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
For more information please refer to the paper at [https://arxiv.org/abs/2509.11481](https://arxiv.org/abs/2509.11481).
## 구조
The RAPTOR control policy is an end-to-end policy that takes position, orientation, linear velocity and angular velocity as inputs and outputs motor commands (`actuator_motors`).
To integrate it into PX4 we use the external mode registration facilities in PX4 (which also works well for internal modes as demonstrated in `mc_nn_control`).
Because of this architecture the `mc_raptor` module is completely decoupled from all other PX4 logic.
By default, the RAPTOR module expects setpoints via `trajectory_setpoint` messages.
If no `trajectory_setpoint` messages are received or if no `trajectory_setpoint` is received within 200 ms, the current position and orientation (with zero velocity) is used as the setpoint.
Since feeding setpoints reliably via telemetry is still a challenge, we also implement a simple option to generate internal reference trajectories (controlled through the `MC_RAPTOR_INTREF` parameter) for demonstration and benchmarking purposes.
## 특징
- Tiny neural network (just 2084 parameters) => minimal CPU usage
- Easily maintainable
- Simple CMake setup
- Self-contained (no interference with other modules)
- Single, simple and well-maintained dependency (RLtools)
- Loading neural network parameters from SD card
- Minimal flash usage (for possible inclusion into default build configurations)
- Easy development: Train new neural network and just upload it via MAVLink FTP without requiring to re-flash the firmware
- Tested on 10+ different real platforms (including flexible frames, brushed motors)
- Actively developed and maintained
## 사용법
### SITL
Build PX4 SITL with Raptor, disable QGC requirement, and adjust the `IMU_GYRO_RATEMAX` to match the simulation IMU rate
```sh
make px4_sitl_raptor gz_x500
param set NAV_DLL_ACT 0
param set COM_DISARM_LAND -1 # When taking off in offboard the landing detector can cause mid-air disarms
param set IMU_GYRO_RATEMAX 250 # Just for SITL. Tested with IMU_GYRO_RATEMAX=400 on real FCUs
param set MC_RAPTOR_ENABLE 1 # Enable the mc_raptor module
param save
```
Upload the RAPTOR checkpoint to the "SD card": Separate terminal
```bash
mavproxy.py --master udp:127.0.0.1:14540
ftp mkdir /raptor # for the real FMU use: /fs/microsd/raptor
ftp put src/modules/mc_raptor/blob/policy.tar /raptor/policy.tar
```
Restart (<kbd>Ctrl+C</kbd>)
```sh
make px4_sitl_raptor gz_x500
commander takeoff
commander status
```
Note the external mode ID of `RAPTOR` in the status report
```sh
commander mode ext{RAPTOR_MODE_ID}
```
#### Internal Reference Trajectory Generation
In our experience, feeding the `trajectory_setpoint` via MAVLink (even via WiFi telemetry) is unreliable.
But we do not want to constrain this module to only platforms that have a companion board.
For this reason we have integrated a simple internal reference trajectory generator for testing and benchmarking purposes.
It supports position (constant position and yaw setpoint) as well as configurable [Lissajous trajectories](https://en.wikipedia.org/wiki/Lissajous_curve).
The Lissajous generator can, for example, generate smooth figure-eight trajectories that contain interesting accelerations for benchmarking and testing purposes.
Please refer to the embedded configurator later in this section to explore the Lissajous parameters and view the resulting trajectories.
To use the internal reference generator, select the mode: `0`: Off/activation position tracking, `1`: Lissajous
```sh
param set MC_RAPTOR_INTREF 1
```
Restart (ctrl+c)
```sh
commander takeoff
commander mode ext{RAPTOR_MODE_ID}
mc_raptor intref lissajous 0.5 1 0 2 1 1 10 3
```
The trajectory is relative to the position and yaw of the vehicle at the point where the RAPTOR mode is activated (or the position and yaw where the parameters are changed if it is already activated).
You can adjust the parameters of the trajectory with the following tool.
Make sure to copy the generated CLI string at the end:
<iframe src="https://rl-tools.github.io/mc-raptor-trajectory-tool" width="100%" height="1700" style="border: none;"></iframe>
### Real-World
#### 설정
The `mc_raptor` module has been mostly tested with the Holybro X500 V2 but it should also work out-of-the-box with other platforms (see the [Other Platforms](#other-platforms) section).
```sh
make px4_fmu-v6c_raptor upload
```
We recommend initially testing the RAPTOR mode using a dead man's switch.
For this we configure the mode selection to be connected to a push button or a switch with a spring that automatically switches back.
In the default position we configure e.g. `Stabilized Mode` and in the pressed configuration we select `External Mode 1` (since the name of the external mode is only transmitted at runtime).
This allows to take off manually and then just trigger the RAPTOR mode for a split-second to see how it behaves.
In our experiments it has been exceptionally stable (zero crashes) but we still think progressively activating it for longer is the safest way to build confidence.
:::warning
Make sure that your platform uses the standard PX4 quadrotor motor layout:
1: front-right, 2: back-left, 3: front-left, 4: back-right
:::
##### Other Platforms
To enable the `mc_raptor` module in other platforms, just add `CONFIG_MODULES_MC_RAPTOR=y` and `CONFIG_LIB_RL_TOOLS=y`
```diff
+++ b/boards/px4/fmu-v6c/raptor.px4board
@@ -35,2 +35,3 @@
CONFIG_DRIVERS_UAVCAN=y
+CONFIG_LIB_RL_TOOLS=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
@@ -64,2 +65,3 @@
CONFIG_MODULES_MC_POS_CONTROL=y
+CONFIG_MODULES_MC_RAPTOR=y
CONFIG_MODULES_MC_RATE_CONTROL=y
```
#### Results
Even though there were moderate winds (~ 5 m/s) during the test, we found good figure-eight tracking performance at velocities up to 12 m/s:
![Lissajous](../../assets/advanced/neural_networks/raptor/results_figure_eight.svg)
We also tested the linear velocity in a straight line and found that the RAPTOR policy can reliably fly at > 17 m/s (the wind direction was orthogonal to the line):
![Linear Oscillation](../../assets/advanced/neural_networks/raptor/results_line.svg)
### 문제 해결
#### 로깅
Use this logging configuration to log all relevant topics at maximum rate:
```sh
cat > logger_topics.txt << EOF
raptor_status 0
raptor_input 0
trajectory_setpoint 0
vehicle_local_position 0
vehicle_angular_velocity 0
vehicle_attitude 0
vehicle_status 0
actuator_motors 0
EOF
```
Use mavproxy FTP to upload it:
```sh
mavproxy.py
```
##### Real
```sh
ftp mkdir /fs/microsd/etc
ftp mkdir /fs/microsd/etc/logging
ftp put logger_topics.txt /fs/microsd/etc/logging/logger_topics.txt
```
##### SITL
```sh
ftp mkdir etc
ftp mkdir logging
ftp put logger_topics.txt etc/logging/logger_topics.txt
```

View File

@ -0,0 +1,77 @@
# TensorFlow Lite Micro (TFLM)
The PX4 [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) integrates a neural network that uses the [TensorFlow Lite Micro (TFLM)](https://github.com/tensorflow/tflite-micro) inference library.
This is a mature inference library intended for use on embedded devices, and is hence a suitable choice for PX4.
This guide explains how the TFLM library is integrated into the [mc_nn_control](../modules/modules_controller.md#mc-nn-control) module, and the changes you would have to make to use it for your own neural network.
:::tip
For more information, see the [TFLM guide](https://ai.google.dev/edge/litert/microcontrollers/get_started).
:::
## TLMF NN Formats
TFLM uses networks in its own [tflite format](https://ai.google.dev/edge/litert/models/convert).
However, since many microcontrollers do not have native filesystem support, a tflite file can be converted to a C++ source and header file.
This is what is done in `mc_nn_control`.
The tflight neural network is represented in code by the files [`control_net.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/control_net.cpp) and [`control_net.hpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/control_net.hpp).
### Getting a Network in tflite Format
There are many online resource for generating networks in the `.tflite` format.
For this example we trained the network in the open source [Aerial Gym Simulator](https://ntnu-arl.github.io/aerial_gym_simulator/).
Aerial Gym includes a guide, and supports RL both for control and vision-based navigation tasks.
The project includes conversion code for `PyTorch -> TFLM` in the [resources/conversion](https://github.com/ntnu-arl/aerial_gym_simulator/tree/main/resources/conversion) folder.
### Updating `mc_nn_control` with your own NN
You can convert a `.tflite` network into a `.cc` file in the ubuntu terminal with this command:
```sh
xxd -i converted_model.tflite > model_data.cc
```
You will then have to modify the `control_net.hpp` and `control_net.cpp` to include the data from `model_data.cc`:
- Take the size of the network in the bottom of the `.cc` file and replace the size in `control_net.hpp`.
- Take the data in the model array in the `cc` file, and replace the ones in `control_net.cpp`.
You are now ready to run your own network.
## Code Explanation
This section explains the code used to integrate the NN in `control_net.cpp`.
### Operations and Resolver
Firstly we need to create the resolver and load the needed operators to run inference on the NN.
This is done in the top of `mc_nn_control.cpp`.
The number in `MicroMutableOpResolver<3>` represents how many operations you need to run the inference.
A full list of the operators can be found in the [micro_mutable_op_resolver.h](https://github.com/tensorflow/tflite-micro/blob/main/tensorflow/lite/micro/micro_mutable_op_resolver.h) file.
There are quite a few supported operators, but you will not find the most advanced ones.
In the control example the network is fully connected so we use `AddFullyConnected()`.
Then the activation function is ReLU, and we `AddAdd()` for the bias on each neuron.
### Interpreter
In the `InitializeNetwork()` we start by setting up the model that we loaded from the source and header file.
Next is to set up the interpreter, this code is taken from the TFLM documentation and is thoroughly explained there.
The end state is that the `_control_interpreter` is set up to later run inference with the `Invoke()` member function.
The `_input_tensor` is also defined, it is fetched from `_control_interpreter->input(0)`.
### 입력
The `_input_tensor` is filled in the `PopulateInputTensor()` function.
`_input_tensor` works by accessing the `->data.f` member array and fill in the required inputs for your network.
The inputs used in the control network is covered in [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md).
### 출력
For the outputs the approach is fairly similar to the inputs.
After setting the correct inputs, calling the `Invoke()` function the outputs can be found by getting `_control_interpreter->output(0)`.
And from the output tensor you get the `->data.f` array.

View File

@ -151,6 +151,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### uXRCE-DDS / ROS2
- [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): <Badge type="warning" text="Experimental"/> [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically
- <Badge type="warning" text="Experimental"/>[PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md).
- dds_topics: add vtol_vehicle_status ([PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582))
- dds_topics: add home_position ([PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583))

134
docs/ko/releases/1.17.md Normal file
View File

@ -0,0 +1,134 @@
# PX4-Autopilot v1.17.0 Release Notes
<Badge type="danger" text="Alpha/Beta" />
<script setup>
import { useData } from 'vitepress'
const { site } = useData();
</script>
<div v-if="site.title !== 'PX4 Guide (main)'">
<div class="custom-block danger">
<p class="custom-block-title">This page is on a release branch, and hence probably out of date. <a href="https://docs.px4.io/main/en/releases/main.html">See the latest version</a>.</p>
</div>
</div>
This contains changes to PX4 planned for PX4 v1.17 (since the last major release [PX v1.16](../releases/1.16.md)).
:::warning
PX4 v1.17 is in alpha/beta testing.
Update these notes with features that are going to be in PX4 v1.17 release.
New features that are not expected to go into the v1.17 release are in [PX4-Autopilot `main` Release Notes](../releases/main.md).
:::
## Read Before Upgrading
TBD …
Please continue reading for [upgrade instructions](#upgrade-guide).
## Major Changes
- TBD
## Upgrade Guide
## Other changes
### Hardware Support
- **[New Hardware]** boards: [MicoAir743-Lite FC](../flight_controller/micoair743-lite.md) <!-- CHECK is this version and add PR link (or fix up doc version tag and move this) -->
- **[New Hardware]** boards: [RadiolinkPIX6 FC](../flight_controller/radiolink_pix6.md) <!-- CHECK is this version and add PR! -->
- **[New Hardware]** boards: [AP-H743-R1 FC](../flight_controller/x-mav_ap-h743r1.md) <!-- CHECK is this version and add PR! -->
<!--
### Common
- [QGroundControl Bootloader Update](../advanced_config/bootloader_update.md#qgc-bootloader-update-sys-bl-update) via the [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE) parameter has been re-enabled after being broken for a number of releases. ([PX4-Autopilot#25032: build: romf: fix generation of rc.board_bootloader_upgrade](https://github.com/PX4/PX4-Autopilot/pull/25032)).
-->
### 제어
<!--
- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
-->
- <Badge type="warning" text="Experimental" /> [MC Neural Network Module](../advanced/neural_networkss.md)
### Estimation
- TBD
<!--
### Sensors
- Add [sbgECom INS driver](../sensor/sbgecom.md) ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137))
- Quick magnetometer calibration now supports specifying an arbitrary initial heading ([PX4-Autopilot#24637](https://github.com/PX4/PX4-Autopilot/pull/24637))
-->
### 시뮬레이션
- Overhaul rover simulation:
- Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107)
- Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113)
- Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117)
- [Simulation-in-Hardware (SIH)](../sim_sih/index.md#compatibility) <!-- Listed in https://docs.px4.io/main/en/sim_sih/#compatibility : Check the PRs -->
- New simulation: MC Hexacopter X
- New simulation: Ackermann Rover
### Debug & Logging
- TBD
### Ethernet
- TBD
### uXRCE-DDS / Zenoh / ROS2
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)).
- [UXRCE_DDS: Simple index based namespace (UXRCE_DDS_NS_IDX)](../middleware/uxrce_dds.md#customizing-the-namespace)
- [Zenoh (PX4 ROS 2 rmw_zenoh)](../middleware/zenoh.md)
### MAVLink
- TBD
<!--
### RC
- Parse ELRS Status and Link Statistics TX messages in the CRSF parser.
### Multi-Rotor
- Removed parameters `MPC_{XY/Z/YAW}_MAN_EXPO` and use default value instead, as they were not deemed necessary anymore. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
- Renamed `MPC_HOLD_DZ` to `MAN_DEADZONE` to have it globally available in modes that allow for a dead zone. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
-->
### 수직이착륙기(VTOL)
- TBD
### Fixed-wing
- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) will now keep climbing with level wings on position loss.
A target takeoff waypoint can be set to control takeoff course and loiter altitude. ([PX4-Autopilot#25083](https://github.com/PX4/PX4-Autopilot/pull/25083)).
- Automatically suppress angular rate oscillations using [Gain compression](../features_fw/gain_compression.md). ([PX4-Autopilot#25840: FW rate control: add gain compression algorithm](https://github.com/PX4/PX4-Autopilot/pull/25840))
### 탐사선
- Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)).
- Add support for [Apps & API](../flight_modes_rover/api.md) including [Rover Setpoints](../ros2/px4_ros2_control_interface.md#rover-setpoints) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)).
- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details).
### ROS 2
- TBD

View File

@ -2,7 +2,8 @@
PX4 릴리스 노트는 각 릴리스의 변경 사항들을 설명합니다.
- [main](../releases/main.md) (changes since v1.16)
- [main](../releases/main.md) (changes planned for v1.18 or later)
- [v1.17](../releases/1.17.md) (changes planned for v1.17, since v1.16)
- [v1.16](../releases/1.16.md)
- [v1.15](../releases/1.15.md)
- [v1.14](../releases/1.14.md)

View File

@ -16,13 +16,13 @@ const { site } = useData();
This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)).
:::warning
PX4 v1.16 is in candidate-release testing, pending release.
Update these notes with features that are going to be in `main` but not the PX4 v1.16 release.
PX4 v1.17 is in alpha/beta testing.
Update these notes with features that are going to be in `main` (PX4 v1.18 or later) but not the PX4 v1.17 release.
:::
## Read Before Upgrading
TBD …
- TBD …
Please continue reading for [upgrade instructions](#upgrade-guide).
@ -45,8 +45,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### 제어
- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. (PX4-Autopilot#25435: Add new flight mode: Altitude Cruise
).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
### Estimation
@ -59,19 +58,34 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### 시뮬레이션
- TBD
<!-- MOVED THIS TO v1.17
- Overhaul rover simulation:
- Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107)
- Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113)
- Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117)
-->
### Debug & Logging
- [Asset Tracking](../debug/asset_tracking.md): Automatic tracking and logging of external device information including vendor name, firmware and hardware version, serial numbers. Currently supports DroneCAN devices. ([PX4-Autopilot#25617](https://github.com/PX4/PX4-Autopilot/pull/25617))
### Ethernet
- TBD
### uXRCE-DDS / ROS2
### uXRCE-DDS / Zenoh / ROS2
- TBD
<!-- MOVED THIS TO v1.17
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)).
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md).
-->
### MAVLink
@ -92,16 +106,26 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Fixed-wing
- TBD
<!-- MOVED THIS TO v1.17
- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) will now keep climbing with level wings on position loss.
A target takeoff waypoint can be set to control takeoff course and loiter altitude. ([PX4-Autopilot#25083](https://github.com/PX4/PX4-Autopilot/pull/25083)).
- Automatically suppress angular rate oscillations using [Gain compression](../features_fw/gain_compression.md). ([PX4-Autopilot#25840: FW rate control: add gain compression algorithm](https://github.com/PX4/PX4-Autopilot/pull/25840))
-->
### 탐사선
- TBD
<!-- MOVED THIS TO v1.17
- Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)).
- Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)).
- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details).
-->
### ROS 2
- TBD

View File

@ -345,9 +345,9 @@ The used types also define the compatibility with different vehicle types.
The following sections provide a list of supported setpoint types:
- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): <Badge type="warning" text="MC only" /> Smooth position and (optionally) heading control
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="PX4 v1.17" /> Direct control of lateral and longitudinal fixed wing dynamics
- [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints
- [Rover Setpoints](#rover-setpoints): <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering).
- [Rover Setpoints](#rover-setpoints): <Badge type="tip" text="PX4 v1.17" /> Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering).
:::tip
The other setpoint types are currently experimental, and can be found in: [px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental).
@ -414,7 +414,7 @@ _goto_setpoint->update(
#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType)
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="PX4 v1.17" />
:::info
This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode.
@ -556,7 +556,7 @@ If you want to control an actuator that does not control the vehicle's motion, b
#### Rover Setpoints
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
The rover modules use a hierarchical structure to propagate setpoints:
@ -590,7 +590,7 @@ An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpoint
### Controlling a VTOL
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration:

View File

@ -27,8 +27,8 @@ The Desktop computer is only used to display the virtual vehicle.
- SIH for FW (airplane) and VTOL tailsitter are supported from PX4 v1.13.
- SIH as SITL (without hardware) from PX4 v1.14.
- SIH for Standard VTOL from PX4 v1.16.
- SIH for MC Hexacopter X from `main` (expected to be PX4 v1.17).
- SIH for Ackermann Rover from `main`.
- SIH for MC Hexacopter X from PX4 v1.17.
- SIH for Ackermann Rover from PX4 v1.17.
### Benefits

View File

@ -93,6 +93,7 @@
- [Настройка Зворотнього Переходу](config_vtol/vtol_back_transition_tuning.md)
- [ВЗІП Датчик польоту](config_vtol/vtol_without_airspeed_sensor.md)
- [VTOL Weather Vane](config_vtol/vtol_weathervane.md)
- [VTOL Ice Shedding](config_vtol/vtol_ice_shedding.md)
- [Режим польоту](flight_modes_vtol/index.md)
- [Mission Mode (VTOL)](flight_modes_vtol/mission.md)
- [Return Mode (VTOL)](flight_modes_vtol/return.md)
@ -128,6 +129,7 @@
- [Значення світлодіодів](getting_started/led_meanings.md)
- [Значення звуків та мелодій](getting_started/tunes.md)
- [QGroundControl Flight-Readiness Status](flying/pre_flight_checks.md)
- [Asset Tracking](debug/asset_tracking.md)
- [Вибір обладнання & Налаштування](hardware/drone_parts.md)
- [Flight Controllers (Autopilots)](flight_controller/index.md)
@ -273,6 +275,8 @@
- [Holybro M8N & M9N GPS](gps_compass/gps_holybro_m8n_m9n.md)
- [Sky-Drones SmartAP GPS](gps_compass/gps_smartap.md)
- [RTK GNSS](gps_compass/rtk_gps.md)
- [ARK G5 RTK GPS](dronecan/ark_g5_rtk_gps.md)
- [ARK G5 RTK HEADING GPS](dronecan/ark_g5_rtk_heading_gps.md)
- [ARK RTK GPS (CAN)](dronecan/ark_rtk_gps.md)
- [ARK RTK GPS L1 L5 (CAN)](dronecan/ark_rtk_gps_l1_l2.md)
- [ARK X20 RTK GPS (CAN)](dronecan/ark_x20_rtk_gps.md)
@ -358,6 +362,8 @@
- [Супутниковий зв'язок (Iridium/RockBlock)](advanced_features/satcom_roadblock.md)
- [Analog Video Transmitters](vtx/index.md)
- [Енергетичні системи](power_systems/index.md)
- [Налаштування оцінки батареї](config/battery.md)
- [Battery Chemistry Overview](power_systems/battery_chemistry.md)
@ -840,9 +846,11 @@
- [Інтеграція камери/Архітектура](camera/camera_architecture.md)
- [Комп'ютерний зір](advanced/computer_vision.md)
- [Захоплення руху (VICON, Optitrack, NOKOV)](tutorials/motion-capture.md)
- [Neural Networks](advanced/neural_networks.md)
- [Neural Network Module Utilities](advanced/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](advanced/tflm.md)
- [Neural Networks](neural_networks/index.md)
- [MC NN Control Module (Generic)](neural_networks/mc_neural_network_control.md)
- [Neural Network Module Utilities](neural_networks/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](neural_networks/tflm.md)
- [RAPTOR Adaptive RL NN Module](neural_networks/raptor.md)
- [Встановлюється драйвер для Intel RealSense R200](advanced/realsense_intel_driver.md)
- [Перемикання оцінювачів стану](advanced/switching_state_estimators.md)
- [Out-of-Tree модулі](advanced/out_of_tree_modules.md)
@ -925,6 +933,7 @@
- [Релізи](releases/index.md)
- [main (alpha)](releases/main.md)
- [1.17 (alpha)](releases/1.17.md)
- [1.16 (stable)](releases/1.16.md)
- [1.15](releases/1.15.md)
- [1.14](releases/1.14.md)

View File

@ -74,7 +74,7 @@ Gimbal також можна контролювати шляхом підклю
![Gimbal Actuator config](../../assets/config/actuators/qgc_actuators_gimbal.png)
PWM значення для використання при відблокованому, максимальному та мінімальному значеннях можна визначити так само, як і для інших сервоприводів, використовуючи [повзунки тесту приводу](../config/actuators.md#actuator-testing), щоб підтвердити, що кожний повзунок переміщує відповідну вісь, і змінюючи значення так, щоб гімбал знаходився у відповідному положенні при відблокованому стані, низькому і високому положенні повзунка.
The PWM values to use for the disarmed, maximum, center and minimum values can be determined in the same way as other servo, using the [Actuator Test sliders](../config/actuators.md#actuator-testing) to confirm that each slider moves the appropriate axis, and changing the values so that the gimbal is in the appropriate position at the disarmed, low, center and high position in the slider.
Значення також можуть бути наведені у документації гімбала.
## Gimbal Control in Missions

View File

@ -1,119 +1 @@
# Neural Networks
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4.
It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on.
The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md) module.
The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame.
While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle.
Note that after training the network you will need to update and rebuild PX4.
TLFM is a mature inference library intended for use on embedded devices.
It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use.
If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview).
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
## Neural Network PX4 Firmware
:::warning
This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04).
:::
The module has been tested on a number of configurations, which can be build locally using the commands:
```sh
make px4_sitl_neural
```
```sh
make px4_fmu-v6c_neural
```
```sh
make mro_pixracerpro_neural
```
You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines:
```sh
CONFIG_LIB_TFLM=y
CONFIG_MODULES_MC_NN_CONTROL=y
```
:::tip
The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV.
:::
## Example Module Overview
The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below:
![neural_control](../../assets/advanced/neural_control.png)
In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow.
We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow.
We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md)
### Вхід
The input can be changed to whatever you want.
Set up the input you want to use during training and then provide the same input in PX4.
In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order:
- [3] Local position error. (goal position - current position)
- [6] The first 2 rows of a 3 dimensional rotation matrix.
- [3] Linear velocity
- [3] Angular velocity
All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function.
PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation.
Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one.
![ENU-NED](../../assets/advanced/ENU-NED.png)
ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure.
### Output
The output consists of 4 values, the motor forces, one for each motor.
These are transformed in the `RescaleActions()` function.
This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values.
So the output from the network needs to be normalized before they can be sent to the motors in PX4.
The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic.
The publishing is handled in `PublishOutput(float* command_actions)` function.
:::tip
If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned.
Decrease it for more thrust.
:::
## Training your own Network
The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md).
But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended.
Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU.
If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/).
You should do one system identification flight for this and get an approximate inertia matrix for your platform.
On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md).
Then do the following steps:
- Do a hover flight
- Read of the logs what RPM is required for the drone to hover.
- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform.
- Insert these values into the Aerial Gym configuration and train your network.
- Convert the network as explained in [TFLM](tflm.md).
<Redirect to="../neural_networks/mc_neural_network_control" />

View File

@ -10,6 +10,10 @@ CAN it is designed to be democratic and uses differential signaling.
For this reason it is very robust even over longer cable lengths (on large vehicles), and avoids a single point of failure.
CAN також дозволяє отримання зворотного зв'язку від периферійних пристроїв та зручне оновлення прошивки через шину.
PX4 has the ability to track and log detailed information from CAN devices, including firmware versions, hardware versions, and serial numbers.
This enables unique identification and lifecycle tracking of hardware connected to the flight controller.
See [Asset Tracking](../debug/asset_tracking.md) for more information.
PX4 підтримує два програмні протоколи для взаємодії з пристроями CAN:
- [DroneCAN](../dronecan/README.md): PX4 рекомендує це для більшості типових налаштувань.

View File

@ -104,7 +104,7 @@ There are several other "battery related" failsafe mechanisms that may be config
| Налаштування | Параметр | Опис |
| -------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None, `1`: Warning, `3`: Return mode (default). |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None (default), `1`: Warning, `3`: Return mode. |
| <a id="COM_FLT_TIME_MAX"></a> Maximum flight time failsafe level | [COM_FLT_TIME_MAX](../advanced_config/parameter_reference.md#COM_FLT_TIME_MAX) | Maximum allowed flight time before Return mode will be engaged, in seconds. `-1`: Disabled (default). |
## Manual Control Loss Failsafe
@ -119,36 +119,32 @@ PX4 and the receiver may also need to be configured in order to _detect RC loss_
![Safety - RC Loss (QGC)](../../assets/qgc/setup/safety/safety_rc_loss.png)
The QGCroundControl Safety UI allows you to set the [failsafe action](#failsafe-actions) and [RC Loss timeout](#COM_RC_LOSS_T).
Users that want to disable the RC loss failsafe in specific automatic modes (mission, hold, offboard) can do so using the parameter [COM_RCL_EXCEPT](#COM_RCL_EXCEPT).
The QGCroundControl Safety UI allows you to set the [failsafe action](#failsafe-actions) and [manual control loss timeout](#COM_RC_LOSS_T).
Users that want to disable this failsafe in specific modes can do so using the parameter [COM_RCL_EXCEPT](#COM_RCL_EXCEPT).
Нижче наведено додаткові (і базові) налаштування параметрів.
| Параметр | Налаштування | Опис |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_RC_LOSS_T"></a>[COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Аварійний режим втрати ручного керування Timeout | Час після отримання останньої встановленої точки від вибраного джерела керування вручну, після якого керування вважається втраченим. Це повинно бути коротким, оскільки транспортний засіб продовжуватиме літати за старими налаштуваннями керування вручну, поки не спрацює таймаут. |
| <a id="COM_RC_LOSS_T"></a>[COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Аварійний режим втрати ручного керування Timeout | Час після отримання останньої встановленої точки від вибраного джерела керування вручну, після якого керування вважається втраченим. This must be kept short because the vehicle will continue to fly using the last known stick position until the timeout triggers. |
| <a id="COM_FAIL_ACT_T"></a>[COM_FAIL_ACT_T](../advanced_config/parameter_reference.md#COM_FAIL_ACT_T) | Затримка відмови від дії | Delay in seconds between failsafe condition being triggered (`COM_RC_LOSS_T`) and failsafe action (RTL, Land, Hold). У цьому стані транспортний засіб очікує в режимі утримання на повторне підключення джерела керування вручну. Це може бути встановлено довше для довгих польотів, щоб втрата інтермітентного з'єднання не викликала негайного виклику аварійного режиму. Це може бути рівним нулю, щоб аварійний запобіжник спрацював негайно. |
| <a id="NAV_RCL_ACT"></a>[NAV_RCL_ACT](../advanced_config/parameter_reference.md#NAV_RCL_ACT) | Моделювання відмовостійкості | Вимкнути, Блукати, Повернутися, Приземлитися, Роззброїти, Завершити. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | Виключення втрат RC | Встановіть режими, в яких втрата керування вручну ігнорується: Місія, Утримання, Offboard. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | Виключення втрат RC | Set modes in which manual control loss is ignored. |
## Втрата каналу зв'язку Failsafe
Збій втрати втрати даних посилання (при переході через телеметрію (підключення до наземної станції) втрачено.
The Data Link Loss failsafe is triggered if the connection to the last MAVLink ground station like QGroundControl is lost.
Users that want to disable this failsafe in specific modes can do so using the parameter [COM_DLL_EXCEPT](#COM_DLL_EXCEPT).
![Safety - Data Link Loss (QGC)](../../assets/qgc/setup/safety/safety_data_link_loss.png)
Налаштування та вибрані параметри показані нижче.
| Налаштування | Параметр | Опис |
| ------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------- |
| Тайм-аут втрати каналу зв'язку | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Час після втрати з'єднання з даними перед тим, як спрацює запобіжник. |
| Моделювання відмовостійкості | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Вимкнути, Hold mode, Return mode, Land mode, Роззброїти, Завершити. |
Також застосовуються наступні налаштування, але вони не відображаються в інтерфейсі QGC.
| Налаштування | Параметр | Опис |
| ----------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- |
| <a id="COM_DLL_EXCEPT"></a>Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes where DL loss will not trigger a failsafe. |
| Налаштування | Параметр | Опис |
| ----------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------- |
| Тайм-аут втрати каналу зв'язку | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Час після втрати з'єднання з даними перед тим, як спрацює запобіжник. |
| Моделювання відмовостійкості | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Вимкнути, Hold mode, Return mode, Land mode, Роззброїти, Завершити. |
| <a id="COM_DLL_EXCEPT"></a>Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes in which data link loss is ignored. |
## Аварійний режим "обмеження зони політів"

View File

@ -9,3 +9,4 @@ As part of this you should calibrate the [Airspeed sensor](../config/airspeed.md
- [Back-transition Tuning](../config_vtol/vtol_back_transition_tuning.md)
- [VTOL w/o Airspeed Sensor](../config_vtol/vtol_without_airspeed_sensor.md)
- [VTOL Weather Vane](../config_vtol/vtol_weathervane.md)
- [Ice Shedding](../config_vtol/vtol_ice_shedding.md)

View File

@ -0,0 +1,22 @@
# VTOL Ice Shedding feature
## Загальний огляд
Ice shedding is a feature that periodically spins unused motors in fixed-wing
flight, to break off any ice that is starting to build up in the motors while it
is still feasible to do so.
It is configured by the paramter `CA_ICE_PERIOD`. When it is 0, the feature is
disabled, when it is above 0, it sets the duration of the ice shedding cycle in
seconds. In each cycle, the rotors are spun for two seconds at a motor output of
0.01.
:::warning
When enabling the feature on a new airframe, there is the risk of producing
torques that disturb the fixed-wing rate controller. To mitigate this risk:
- Set your `PWM_MIN` values correctly, so that the motor output 0.01 actually
produces 1% thrust
- Be prepared to take control and switch back to multicopter
:::

View File

@ -34,7 +34,7 @@ Not all PX4 source code matches the style guide, but any _new code_ that you wri
### Довжина рядка
- Максимальна довжина рядка становить 120 символів.
- Maximum line length is 140 characters.
### Розширення файлів

View File

@ -0,0 +1,68 @@
# Asset Tracking
<Badge type="tip" text="main (planned for: PX4 v1.18)" />
PX4 can track and log detailed information about external hardware devices connected to the flight controller.
This enables unique identification of vehicle parts throughout their operational lifetime using device IDs, serial numbers, and version information.
:::info
Asset tracking is currently implemented for [DroneCAN](../dronecan/index.md) devices only.
:::
## Загальний огляд
Asset tracking allows you to determine exactly which hardware is installed on a vehicle, providing serial number, version, and other information.
This makes it easier to track and maintain specific vehicle parts across multiple vehicles, to quickly see what versions you're running when debugging, and log component information for regulatory audits.
Asset tracking automatically collects and logs the following metadata from external devices:
- **Device identification**: Vendor name, model name, device type
- **Version information**: Firmware version, hardware version
- **Unique identifiers**: Serial number, device ID
- **Device capabilities**: ESC, GPS, magnetometer, barometer, etc.
This information is published via the [`device_information`](../msg_docs/DeviceInformation.md) uORB topic and logged to flight logs.
This enables fleet management, maintenance tracking, and troubleshooting.
## Viewing Device Information
### Real-Time Monitoring
You can view device information in real-time using the [MAVLink Shell](../debug/mavlink_shell.md) or console:
```sh
listener device_information
```
Example output for a CAN GPS module:
```plain
TOPIC: device_information
device_information
timestamp: 16258961403 (0.216525 seconds ago)
device_id: 8944643 (Type: 0x88, UAVCAN:0 (0x7C))
device_type: 5
vendor_name: "cubepilot"
model_name: "here4"
firmware_version: "1.14.3006590"
hardware_version: "4.19"
serial_number: "1c00410018513331"
```
Device information is published in a round-robin fashion for each detected device, at a rate of approximately 1 Hz.
### Multi-Capability Devices
Devices with multiple sensors (e.g., a CAN GPS/magnetometer combo module like the HERE4) register separate device information entries for each capability.
Each entry shares the same serial number and base metadata but has a different `device_id` corresponding to the specific sensor capability.
## Аналіз журналу польотів
Device information is automatically logged to flight logs.
You can extract it using [pyulog](../log/flight_log_analysis.md#pyulog), though note that fields like vendor name, model name, and serial number are stored as `char` arrays and require additional parsing.
## Дивіться також
- [CAN (DroneCAN & Cyphal)](../can/index.md) — CAN bus configuration and setup
- [DroneCAN](../dronecan/index.md) — DroneCAN-specific documentation
- [Flight Log Analysis](../log/flight_log_analysis.md) — Flight log analysis

View File

@ -0,0 +1,112 @@
# ARK G5 RTK GPS
:::info
This GPS module is made in the USA and NDAA compliant.
:::
[ARK G5 RTK GPS](https://arkelectron.com/product/ark-g5-rtk-gps/) is a [DroneCAN](index.md) quad-band [RTK GPS](../gps_compass/rtk_gps.md).
The module incorporates the [Septentrio mosaic-G5 P3 Ultra-compact high-precision GPS/GNSS receiver module](https://www.u-blox.com/en/product/zed-x20p-module), magnetometer, barometer, IMU, and buzzer module.
![ARK G5 RTK GPS](../../assets/hardware/gps/ark/ark_g5_rtk_gps.png)
## Де купити
Замовте цей модуль з:
- [ARK Electronics](https://arkelectron.com/product/ark-g5-rtk-gps/) (US)
## Характеристики обладнання
- [DroneCAN](index.md) RTK GNSS, Magnetometer, Barometer, IMU, and Buzzer Module
- [Dronecan Firmware Updating](../dronecan/index.md#firmware-update)
- Датчики
- [Septentrio mosaic-G5 P3 Ultra-compact high-precision GPS/GNSS receiver module](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3)
- All-band all constellation GNSS receiver
- All-in-view satellite tracking: multi-constellation, quad-band GNSS module receiver
- Full raw data with positioning measurements and Galileo HAS positioning service compatibility
- Best-in-class RTK cm-level positioning accuracy
- Advanced GNSS+ algorithms
- 20Hz update rate
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
- [Bosch BMP390 Barometer](https://www.bosch-sensortec.com/products/environmental-sensors/pressure-sensors/bmp390/)
- [Invensense ICM-42688-P 6-Axis IMU](https://invensense.tdk.com/products/motion-tracking/6-axis/icm-42688-p/)
- STM32F412VGH6 MCU
- Кнопка безпеки
- Зумер
- Two CAN Connectors (Pixhawk Connector Standard 4-pin JST GH)
- G5 "UART 2" Connector
- 4-pin JST GH
- TX, RX, PPS, GND
- G5 USB C
- Debug Connector (Pixhawk Connector Standard 6-pin JST SH)
- LED індикатори
- GPS Fix
- Статус RTK
- RGB Статус системи
- USA Built
- NDAA Compliant
- Вимоги до живлення
- 5V
- 270mA
- Розміри
- Without Antenna
- 48.0mm x 40.0mm x 15.4mm
- 13.0g
- With Antenna
- 48.0mm x 40.0mm x 51.0mm
- 43.5g
- Includes
- CAN Cable (Pixhawk Connector Standard 4-pin)
- Full-Frequency Helical GPS Antenna
## Налаштування програмного забезпечення
### Підключення
The ARK G5 RTK GPS is connected to the CAN bus using a [Pixhawk connector standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) 4-pin JST GH cable.
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
### Встановлення
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 Configuration](#px4-configuration).
## Налаштування прошивки
The Septentrio G5 module firmware can be updated using the Septentrio [RxTools](https://www.septentrio.com/en/products/gps-gnss-receiver-software/rxtools) application.
## Налаштування польотного контролера
### Увімкнення DroneCAN
In order to use the ARK G5 RTK GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
Кроки наступні:
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
- Connect ARK G5 RTK GPS CAN to the Pixhawk CAN.
Після активації модуль буде виявлено при завантаженні.
There is also CAN built-in bus termination via [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM)
### Конфігурація PX4
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK G5 RTK GPS from the vehicle's centre of gravity.
## Значення LED індикаторів
The GPS status lights are located to the right of the connectors:
- Миготіння зеленого - це фіксація GPS
- Миготіння синього - це отримані корекції та RTK Float
- Сталий синій - це RTK зафіксовано
## Дивіться також
- [ARK G5 RTK GPS Documentation](https://docs.arkelectron.com/gps/ark-g5-rtk-gps) (ARK Docs)

View File

@ -0,0 +1,150 @@
# ARK G5 RTK HEADING GPS
:::info
This GPS module is made in the USA and NDAA compliant.
:::
[ARK G5 RTK HEADING GPS](https://arkelectron.com/product/ark-g5-rtk-gps/) is a [DroneCAN](index.md) quad-band dual antenna [RTK GPS](../gps_compass/rtk_gps.md) that additionally provides vehicle yaw information from GPS.
The module incorporates the [Septentrio mosaic-G5 P3H Ultra-compact high-precision GPS/GNSS receiver module with heading capability](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H), magnetometer, barometer, IMU, and buzzer module.
![ARK G5 RTK HEADING GPS](../../assets/hardware/gps/ark/ark_g5_rtk_gps.png)
## Де купити
Замовте цей модуль з:
- [ARK Electronics](https://arkelectron.com/product/ark-g5-rtk-heading-gps/) (US)
## Характеристики обладнання
- [DroneCAN](index.md) RTK GNSS, Magnetometer, Barometer, IMU, and Buzzer Module
- [Dronecan Firmware Updating](../dronecan/index.md#firmware-update)
- Датчики
- [Septentrio mosaic-G5 P3H Ultra-compact high-precision GPS/GNSS receiver module with heading capability](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H)
- All-band all constellation GNSS receiver
- All-in-view satellite tracking: multi-constellation, quad-band GNSS module receiver
- Full raw data with positioning measurements and Galileo HAS positioning service compatibility
- Best-in-class RTK cm-level positioning accuracy
- Advanced GNSS+ algorithms
- 20Hz update rate
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
- [Bosch BMP390 Barometer](https://www.bosch-sensortec.com/products/environmental-sensors/pressure-sensors/bmp390/)
- [Invensense ICM-42688-P 6-Axis IMU](https://invensense.tdk.com/products/motion-tracking/6-axis/icm-42688-p/)
- STM32F412VGH6 MCU
- Кнопка безпеки
- Зумер
- Two CAN Connectors (Pixhawk Connector Standard 4-pin JST GH)
- G5 "UART 2" Connector
- 4-pin JST GH
- TX, RX, PPS, GND
- G5 USB C
- Debug Connector (Pixhawk Connector Standard 6-pin JST SH)
- LED індикатори
- GPS Fix
- Статус RTK
- RGB Статус системи
- USA Built
- NDAA Compliant
- Вимоги до живлення
- 5V
- 270mA
- Розміри
- Without Antenna
- 48.0mm x 40.0mm x 15.4mm
- 13.0g
- With Antenna
- 48.0mm x 40.0mm x 51.0mm
- 43.5g
- Includes
- CAN Cable (Pixhawk Connector Standard 4-pin)
- Full-Frequency Helical GPS Antenna
## Налаштування програмного забезпечення
### Підключення
The ARK G5 RTK HEADING GPS is connected to the CAN bus using a [Pixhawk connector standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) 4-pin JST GH cable.
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
### Встановлення
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 configuration](#px4-configuration).
## Налаштування прошивки
The Septentrio G5 module firmware can be updated using the Septentrio [RxTools](https://www.septentrio.com/en/products/gps-gnss-receiver-software/rxtools) application.
## Налаштування польотного контролера
### Увімкнення DroneCAN
In order to use the ARK G5 RTK HEADING GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
Кроки наступні:
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
- Connect ARK G5 RTK HEADING GPS CAN to the Pixhawk CAN.
Після активації модуль буде виявлено при завантаженні.
There is also CAN built-in bus termination via [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM)
### Конфігурація PX4
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK G5 RTK HEADING GPS from the vehicle's centre of gravity.
### Parameter references
This GPS is using ARK's private driver, the prameters below only exist on the firmware we ship the GPS with. You can set these params either in QGC or using the DroneCAN GUI Tool.
#### SEP_OFFS_YAW (float)
Heading offset angle for dual antenna GPS setups that support heading estimation.
Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the Rover/ANT2 antenna is in front.
The offset angle increases clockwise.
Set this to 90 if the ANT2 antenna is placed on the right side of the vehicle and the Moving Base/MAIN antenna is on the left side.
- Default: 0
- Min: -360
- Max: 360
- Unit: degree
#### SEP_OFFS_PITCH (float)
Vertical offsets can be compensated for by adjusting the Pitch offset.
Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. Since pitch is defined as the right-handed rotation about the vehicle Y axis, a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch.
- Default: 0
- Min: -90
- Max: 90
- Unit: degree
#### SEP_OUT_RATE (enum)
Configures the output rate for GNSS data messages.
- -1: OnChange (Default)
- 50: 50 ms
- 100: 100 ms
- 200: 200 ms
- 500: 500 ms
## Значення LED індикаторів
The GPS status lights are located to the right of the connectors:
- Миготіння зеленого - це фіксація GPS
- Миготіння синього - це отримані корекції та RTK Float
- Сталий синій - це RTK зафіксовано
## Дивіться також
- [ARK G5 RTK HEADING GPS Documentation](https://docs.arkelectron.com/gps/ark-g5-rtk-gps) (ARK Docs)

View File

@ -27,6 +27,8 @@ DroneCAN was previously known as UAVCAN v0 (or just UAVCAN).
- Проводка менше складна, оскільки ви можете мати один шину для підключення всіх ваших ESC і інших периферійних пристроїв DroneCAN.
- Налаштування стає простіше, оскільки ви налаштовуєте нумерацію ESC, обертаючи кожен двигун вручну.
- Це дозволяє користувачам налаштовувати та оновлювати прошивку всіх пристроїв, підключених через CAN, централізовано через PX4.
- PX4 automatically tracks device information (vendor, model, versions, serial numbers) for maintenance and fleet management.
See [Asset Tracking](../debug/asset_tracking.md).
## Підтримуване обладнання

View File

@ -1,6 +1,6 @@
# Gain compression
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
Automatic gain compression reduces the gains of the angular-rate PID whenever oscillations are detected.
It monitors the angular-rate controller output through a band-pass filter to identify these oscillations.

View File

@ -1,6 +1,6 @@
# MicoAir743-Lite
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
:::warning
PX4 не розробляє цей (або будь-який інший) автопілот.

View File

@ -1,6 +1,6 @@
# RadiolinkPIX6 Flight Controller
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
:::warning
PX4 не розробляє цей (або будь-який інший) автопілот.

View File

@ -1,6 +1,6 @@
# AP-H743-R1
# AP-H743-R1 Flight Controller
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
:::warning
PX4 не розробляє цей (або будь-який інший) автопілот.

Some files were not shown because too many files have changed in this diff Show More