Compare commits

..

1 Commits

Author SHA1 Message Date
FARHANG c77c9186d6 Hacky fixes for macOS build 2026-01-29 18:25:41 -05:00
134 changed files with 449 additions and 5300 deletions
@@ -1,212 +0,0 @@
---
applyTo: "src/drivers/**"
---
# PX4 Driver Review Instructions
This file provides guidelines for reviewing driver files in the `src/drivers/` directory.
## Copyright Statements
### Required Files
All source files (`.cpp`, `.c`, `.hpp`, `.h`, `CMakeLists.txt`) MUST include a copyright statement at the top.
**Exceptions:**
- `Kconfig` files
- `module.yaml` files
### Copyright Format
**For new files (created in 2026):**
```cpp
/****************************************************************************
*
* 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.
*
****************************************************************************/
```
**For updated files (originally created in 2015, updated in 2026):**
```cpp
/****************************************************************************
*
* Copyright (c) 2015-2026 PX4 Development Team. All rights reserved.
*
* [... rest of copyright text ...]
*
****************************************************************************/
```
### Key Points
- First year should be the original creation year
- When updating an existing file, update the year range: `YYYY-2026`
- Use the current year (2026 in this case) for new files
- Maintain consistent formatting with other PX4 driver files
---
## Driver Self-Documentation
All drivers MUST be self-documenting through the `print_usage()` method.
### Required Implementation
Every driver `.cpp` file must implement a `print_usage()` method that includes:
1. **PRINT_MODULE_DESCRIPTION macro** - Contains markdown documentation
2. **Module identification** - Using PRINT_MODULE_USAGE_NAME and optionally PRINT_MODULE_USAGE_SUBCATEGORY
3. **Parameter documentation** - Relevant parameters, especially enablement parameters
### PRINT_MODULE_DESCRIPTION Structure
The description should follow this markdown format:
```cpp
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
[Clear description of what the driver does and its primary functionality]
### Implementation
[Optional: High-level overview of how the driver works]
### Examples
[Optional: CLI usage examples if non-trivial]
$ module_name start -d /dev/ttyS1
$ module_name stop
)DESCR_STR");
```
### Required Sections
#### 1. Description Section
- Brief explanation of the driver's purpose
- Key features/capabilities
- Important parameters (especially enable parameters like `SENS_XX_CFG`)
#### 2. Documentation Links
When applicable, include links to user documentation:
```cpp
Setup/usage information: https://docs.px4.io/main/en/sensor/[sensor-name].html
```
#### 3. Examples Section (when relevant)
Provide CLI usage examples for non-trivial commands:
```cpp
### Examples
Attempt to start driver on a specified serial device.
$ vectornav start -d /dev/ttyS1
Stop driver
$ vectornav stop
```
### Complete Example
```cpp
int MyDriver::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
This driver interfaces with the XYZ sensor via I2C/SPI. It provides
distance measurements and is automatically started when SENS_XYZ_CFG
is set to the appropriate value.
Key features:
- Distance range: 0.2m to 50m
- Update rate: up to 100Hz
- I2C and SPI support
Setup/usage information: https://docs.px4.io/main/en/sensor/xyz_sensor.html
### Examples
Start driver on I2C bus 1 with address 0x29:
$ xyz_sensor start -X -b 1 -a 0x29
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("xyz_sensor", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true);
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x29);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
```
### Common Patterns by Driver Type
**For UART/Serial Drivers:**
```cpp
PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "<file:dev>", "Serial device", true);
```
**For I2C/SPI Drivers:**
```cpp
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true);
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x76);
```
**For Sensor Drivers:**
```cpp
PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); // or imu, magnetometer, etc.
```
---
## Review Checklist
When reviewing driver files, verify:
- [ ] Copyright header is present (except Kconfig and module.yaml)
- [ ] Copyright year is correct (current year for new files, year range for updates)
- [ ] `print_usage()` method exists
- [ ] `PRINT_MODULE_DESCRIPTION` macro is present with markdown content
- [ ] Description section explains driver purpose clearly
- [ ] Relevant parameters are documented (especially enable parameters)
- [ ] Documentation links are included when available
- [ ] Examples are provided for complex CLI usage
- [ ] Module name and category are correctly specified
- [ ] Standard commands (start, stop, status) are documented
---
## Additional Resources
- Driver template examples: `src/drivers/*/` (various sensor types)
- Module macros: `platforms/common/include/px4_platform_common/module.h`
- Similar drivers for reference patterns (DShot, VectorNav, CrsfRc, etc.)
+58 -822
View File
@@ -8,803 +8,6 @@ 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
@@ -924,50 +127,83 @@ 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]
msgTypes.add(msg_name)
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))
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()
#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)
# Categorize as versioned or unversioned
if "versioned" in msg_file:
versioned_msgs_list += f"- [{message.name}]({message.name}.md)"
if message.shortDescription:
versioned_msgs_list += f"{message.shortDescription}"
versioned_msgs_list += '- [%s](%s.md)' % (msg_name, msg_name)
if summary_description:
versioned_msgs_list += "%s" % summary_description
versioned_msgs_list += "\n"
else:
unversioned_msgs_list += f"- [{message.name}]({message.name}.md)"
if message.shortDescription:
unversioned_msgs_list += f"{message.shortDescription}"
unversioned_msgs_list += '- [%s](%s.md)' % (msg_name, msg_name)
if summary_description:
unversioned_msgs_list += "%s" % summary_description
unversioned_msgs_list += "\n"
# Write out the index.md file
index_text=f"""# uORB Message Reference
index_text="""# 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.
@@ -982,14 +218,14 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
## Versioned Messages
{versioned_msgs_list}
%s
## Unversioned Messages
{unversioned_msgs_list}
"""
%s
""" % (versioned_msgs_list, unversioned_msgs_list)
index_file = os.path.join(output_dir, 'index.md')
with open(index_file, 'w', encoding='utf-8') as content_file:
with open(index_file, 'w') as content_file:
content_file.write(index_text)
generate_dds_yaml_doc(msg_files)
-1
View File
@@ -31,7 +31,6 @@ 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
-2
View File
@@ -1,6 +1,4 @@
# 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
@@ -1,3 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROMFSROOT=""
@@ -1,86 +0,0 @@
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
@@ -1,13 +0,0 @@
{
"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
}
@@ -1,17 +0,0 @@
#!/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
@@ -1,6 +0,0 @@
#!/bin/sh
#
# AirBrainH743 specific board extras init
#------------------------------------------------------------------------------
# No extras configured by default
@@ -1,16 +0,0 @@
#!/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
@@ -1,3 +0,0 @@
#
# Board-specific Kconfig for AirBrainH743
#
@@ -1,89 +0,0 @@
#
# 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
@@ -1,346 +0,0 @@
/************************************************************************************
* 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 */
@@ -1,42 +0,0 @@
/****************************************************************************
*
* 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 */
@@ -1,258 +0,0 @@
#
# 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
@@ -1,213 +0,0 @@
/****************************************************************************
* 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) }
}
@@ -1,228 +0,0 @@
/****************************************************************************
* 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) }
}
@@ -1,67 +0,0 @@
############################################################################
#
# 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()
@@ -1,223 +0,0 @@
/****************************************************************************
*
* 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
@@ -1,75 +0,0 @@
/****************************************************************************
*
* 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();
}
@@ -1,85 +0,0 @@
/****************************************************************************
*
* 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
-47
View File
@@ -1,47 +0,0 @@
/****************************************************************************
*
* 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),
};
-249
View File
@@ -1,249 +0,0 @@
/****************************************************************************
*
* 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;
}
-205
View File
@@ -1,205 +0,0 @@
/****************************************************************************
*
* 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 */
-58
View File
@@ -1,58 +0,0 @@
/****************************************************************************
*
* 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);
@@ -1,74 +0,0 @@
/****************************************************************************
*
* 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);
-75
View File
@@ -1,75 +0,0 @@
/****************************************************************************
*
* 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);
}
@@ -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=y
CONFIG_NSH_DISABLE_DF=y
# 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=y
CONFIG_NSH_DISABLE_FREE=y
CONFIG_NSH_DISABLE_GET=y
# 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=y
# 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=y
CONFIG_NSH_DISABLE_PS=y
CONFIG_NSH_DISABLE_PSSTACKUSAGE=y
CONFIG_NSH_DISABLE_PWD=y
# 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=y
# 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=y
# 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
@@ -1,6 +1,5 @@
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"
@@ -38,6 +38,5 @@ param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# W25N NAND flash with littlefs (128 MB): larger buffer, auto-rotate
set LOGGER_BUF 32
param set-default SDLOG_DIRS_MAX 3
# Disable logging
param set-default SDLOG_BACKEND 0
@@ -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/5 = 960 MHz / 5 = 192 MHz (SPI123 clock, max 200 MHz)
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 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(5)
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
#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_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
#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 - PLL1Q = 192 MHz for W25N NAND flash (max 104 MHz) */
/* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL1
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
/* 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)
* PLL1Q = 192 MHz, div = 192 / 50 = 3.84, round up to 4 for 24 MHz
/* 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
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (4 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << 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 (4 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
@@ -33,10 +33,6 @@
#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 */
@@ -104,10 +104,6 @@ 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
@@ -130,9 +126,7 @@ CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
# CONFIG_MTD_RAMTRON is not set
CONFIG_MTD_W25N=y
CONFIG_W25N_SPIFREQUENCY=104000000
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
@@ -141,7 +135,7 @@ CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
# CONFIG_NSH_MMCSDSPIPORTNO is not set
CONFIG_NSH_MMCSDSPIPORTNO=1
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
@@ -154,6 +148,9 @@ 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
@@ -191,7 +188,6 @@ 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
@@ -206,8 +202,6 @@ 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
@@ -59,11 +59,6 @@
# 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 */
+5 -46
View File
@@ -59,8 +59,6 @@
#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>
@@ -81,10 +79,6 @@
# 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
@@ -237,49 +231,14 @@ __EXPORT int board_app_initialize(uintptr_t arg)
led_on(LED_RED);
}
#ifdef CONFIG_MTD_W25N
/* Initialize W25N01GV NAND Flash on SPI1 */
struct spi_dev_s *spi1 = stm32_spibus_initialize(1);
/* Get the SPI port for the microSD slot */
struct spi_dev_s *spi_dev = stm32_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO);
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
}
}
if (!spi_dev) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO);
led_on(LED_BLUE);
}
#endif
up_udelay(20);
+1 -1
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_FLASH(0), SPI::CS{GPIO::PortA, GPIO::Pin4}) // W25N01GV NAND Flash
initSPIDevice(SPIDEV_MMCSD(0), SPI::CS{GPIO::PortA, GPIO::Pin4})
}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}),
+1 -1
View File
@@ -73,7 +73,7 @@ function(px4_add_common_flags)
-Warray-bounds
-Wcast-align
-Wdisabled-optimization
-Wdouble-promotion
# -Wdouble-promotion
-Wfatal-errors
-Wfloat-equal
-Wformat-security
-41
View File
@@ -160,44 +160,3 @@
.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;
}
}
-1
View File
@@ -178,7 +178,6 @@
- [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)
+2 -2
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 (default), `1`: Warning, `3`: Return mode. |
| <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_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/acro.md), [Acro mode (FW)](../flight_modes_fw/acro.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/altitude.md), [Acro mode (FW)](../flight_modes_fw/altitude.md), and [Manual (FW)](../flight_modes_fw/manual.md)).
### Attitude Trigger
@@ -25,7 +25,6 @@ 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)
@@ -1,96 +0,0 @@
# 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).
+1 -1
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="main (planned for: PX4 v1.18)" />: Serial port hardware flow control enable.
- [`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
+1 -1
View File
@@ -27,7 +27,7 @@ Unless the mode is safety-critical, requires strict timing or very high update r
::: 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).
Not all classes have Python bindings yet — the [supported bindings are here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_py/src/px4_ros2).
You are welcome to add and contribute missing classes.
:::
-2
View File
@@ -15,8 +15,6 @@ 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
+1 -1
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 (default), `1`: Warning, `3`: Return mode. |
| <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_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
-3
View File
@@ -93,7 +93,6 @@
- [Настройка Зворотнього Переходу](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)
@@ -362,8 +361,6 @@
- [Супутниковий зв'язок (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)
+1 -1
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 (default), `1`: Warning, `3`: Return mode. |
| <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_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
-1
View File
@@ -9,4 +9,3 @@ 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)
-22
View File
@@ -1,22 +0,0 @@
# 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
:::
+1 -1
View File
@@ -34,7 +34,7 @@ Not all PX4 source code matches the style guide, but any _new code_ that you wri
### Довжина рядка
- Maximum line length is 140 characters.
- Максимальна довжина рядка становить 120 символів.
### Розширення файлів
+1 -5
View File
@@ -89,19 +89,15 @@ 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/).
:::
3. Create and open a new _cmake_ definition file named **CMakeLists.txt**.
@@ -170,7 +166,7 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too
4. 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)).
Скопіюйте текст нижче:
```text
```
menuconfig EXAMPLES_PX4_SIMPLE_APP
bool "px4_simple_app"
default n
@@ -22,11 +22,7 @@ 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.
:::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 .
:::
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
+1 -1
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://raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
<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).
+1 -1
View File
@@ -11,7 +11,7 @@ PX4 traffic avoidance works with ADS-B or FLARM products that supply transponder
Було протестовано з наступними пристроями:
- [PingRX ADS-B Receiver](https://uavionix.com/product/pingrx-pro/) (uAvionix)
- [FLARM](https://www.flarm.com/en/drones/)
- [FLARM](https://flarm.com/products/uav/atom-uav-flarm-for-drones/) <!-- I think originally https://flarm.com/products/powerflarm/uav/ -->
## Налаштування програмного забезпечення
+1 -7
View File
@@ -14,7 +14,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 (with Python bindings) that simplifies controlling PX4 from ROS 2.
[PX4 ROS 2 Interface бібліотека](../ros2/px4_ros2_interface_lib.md) - це бібліотека C++++, яка спрощує контроль PX4 з ROS 2.
Розробники використовують бібліотеку для створення і динамічної реєстрації режимів, написаних за допомогою ROS 2.
Ці режими динамічно реєструються в PX4 і здаються частиною PX4 для наземної станції або іншої зовнішньої системи.
@@ -26,12 +26,6 @@ The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ li
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://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_py/src/px4_ros2).
You are welcome to add and contribute missing classes.
:::
## Загальний огляд
Ця діаграма надає концептуального уявлення про те, як режими інтерфейсу і режими керування будуть взаємодіяти з PX4.
+1 -1
View File
@@ -7,7 +7,7 @@
На момент написання цієї статті, деякі частини бібліотеки інтерфейсу PX4 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.
[PX4 ROS 2 Інтерфейс бібліотеки](https://github.com/Auterion/px4-ros2-interface-lib) є бібліотекою C+++, яка спрощує контроль і взаємодіє з PX4 з ROS 2.
The library provides three high-level interfaces for developers:
-287
View File
@@ -1,287 +0,0 @@
# Analog Video Transmitters
Analog Video Transmitters (VTX) can be controlled by PX4 via a half-duplex UART connection implementing the SmartAudio v1, v2, and v2.1 and Tramp protocols.
The protocols allow writing and reading:
- device status.
- transmission frequency in MHz or via band and channel index.
- transmission power in dBm or mW.
- operation modes.
VTX settings are controlled by parameters and optionally via RC AUX channels or CRSF MSP commands.
The driver stores frequency and power tables that map band/channel indices to actual transmission values.
Configuration is device-specific and set up using the command line interface.
## Початок роботи
Connect the SmartAudio or Tramp pin of the VTX to the TX pin of a free serial port on the flight controller.
Then set the following parameters:
- `VTX_SER_CFG`: Select the serial port used for VTX communication.
- `VTX_DEVICE`: Selects the VTX device (generic SmartAudio/Tramp or a specific device).
Note that since the VTX communication is half-duplex, you can, for example, use the single-pin Radio Controller port for the VTX and use a full duplex TELEM port for CRSF communication.
You should now be able to see the VTX device in the driver status:
```
nsh> vtx status
INFO [vtx] UART device: /dev/ttyS4
INFO [vtx] VTX table "UNINITIALIZED":
INFO [vtx] Power levels:
INFO [vtx] RC mapping: Disabled
INFO [vtx] Parameters:
INFO [vtx] band: 1
INFO [vtx] channel: 1
INFO [vtx] frequency: 0 MHz
INFO [vtx] power level: 1
INFO [vtx] power: 0 = 0 mW
INFO [vtx] pit mode: off
INFO [vtx] SmartAudio v2:
INFO [vtx] band: 1
INFO [vtx] channel: 1
INFO [vtx] frequency: 6110 MHz
INFO [vtx] power level: 1
INFO [vtx] power: 0 mW
INFO [vtx] pit mode: on
INFO [vtx] lock: unlocked
```
:::warning
Without a configured power table, power mappings are unknown and default to 0 mW.
Some VTX devices enter pit mode when power is set to 0, regardless of the `VTX_PIT_MODE` parameter.
:::
## VTX Table Configuration
The VTX table stores frequency and power mappings for your specific device.
The manufacturer usually provides this information in the form of a JSON file that can be translated into a [Betaflight CLI command set](https://www.betaflight.com/docs/development/VTX#vtx-table) that this driver implements for compatibility.
### Power Level Configuration
```
# Set table name ≤16 characters
vtxtable name "Peak THOR T67"
# Set the power values that are sent to the VTX for each power level index
# Note: SmartAudio v1 and v2 use index values!
vtxtable powervalues 0 1 2 3 4
# Note: SmartAudio v2.1 uses dBm values instead!
# vtxtable powervalues 14 23 27 30 35
# Note: Tramp uses mW values instead!
# vtxtable powervalues 25 200 500 1000 3000
# Set the corresponding power labels for each power level index ≤4 characters.
# These are used for status reporting.
vtxtable powerlabels 25 200 500 1W 3W
# Set number of power levels
vtxtable powerlevels 5
# Save configuration
vtxtable save
```
This will create a VTX table with 5 power levels.
```nsh> vtxtable status
INFO [vtxtable] VTX table "Peak THOR T67":
INFO [vtxtable] Power levels:
INFO [vtxtable] 1: 0 = 25
INFO [vtxtable] 2: 1 = 200
INFO [vtxtable] 3: 2 = 500
INFO [vtxtable] 4: 3 = 1W
INFO [vtxtable] 5: 4 = 3W
```
### Frequency Table Configuration
```
# Set the name of each band and the frequencies of each channel
vtxtable band 1 BAND_A A FACTORY 6110 6130 6150 6170 6190 6210 6230 6250
vtxtable band 2 BAND_B B FACTORY 6270 6290 6310 6330 6350 6370 6390 6410
vtxtable band 3 BAND_E E FACTORY 6430 6450 6470 6490 6510 6530 6550 6570
vtxtable band 4 BAND_F F FACTORY 6590 6610 6630 6650 6670 6690 6710 6730
vtxtable band 5 BAND_R R FACTORY 6750 6770 6790 6810 6830 6850 6870 6890
vtxtable band 6 BAND_P P FACTORY 6910 6930 6950 6970 6990 7010 7030 7050
vtxtable band 7 BAND_H H FACTORY 7070 7090 7110 7130 7150 7170 7190 7210
vtxtable band 8 BAND_U U FACTORY 6115 6265 6425 6585 6745 6905 7065 7185
# Set number of bands and channels
vtxtable bands 8
vtxtable channels 8
# Save configuration
vtxtable save
```
This will create a VTX table with 8 bands and 8 channels.
Note that FACTORY sends the band and channel indexes to the VTX device and they use their internal frequency mapping. In this mode the frequency is just for indication purposes.
In contrast, CUSTOM would send the actual frequency values to the VTX device, but not all devices support this mode.
Setting a frequency to zero will skip setting it.
```
nsh> vtxtable status
INFO [vtxtable] VTX table 8x8: Peak THOR T67
INFO [vtxtable] A: BAND_A = 6110 6130 6150 6170 6190 6210 6230 6250
INFO [vtxtable] B: BAND_B = 6270 6290 6310 6330 6350 6370 6390 6410
INFO [vtxtable] E: BAND_E = 6430 6450 6470 6490 6510 6530 6550 6570
INFO [vtxtable] F: BAND_F = 6590 6610 6630 6650 6670 6690 6710 6730
INFO [vtxtable] R: BAND_R = 6750 6770 6790 6810 6830 6850 6870 6890
INFO [vtxtable] P: BAND_P = 6910 6930 6950 6970 6990 7010 7030 7050
INFO [vtxtable] H: BAND_H = 7070 7090 7110 7130 7150 7170 7190 7210
INFO [vtxtable] U: BAND_U = 6115 6265 6425 6585 6745 6905 7065 7185
```
### Table Constraints
Maximum table dimensions:
- ≤24 bands each with ≤16 channels and ≤32GHz frequency values.
- ≤16 power levels.
- ≤16 characters table name.
- ≤12 characters band name and 1 character band letter.
- ≤4 characters power label length (to support "2.5W").
## AUX Channel Mapping
The AUX mapping feature allows you to control VTX settings using RC AUX channels.
Each mapping entry defines an AUX channel range that triggers a specific VTX configuration.
To enable AUX mapping, set `VTX_MAP_CONFIG` to one of the following values:
- `0`: Disabled
- `1`: Disabled (reserved for CRSF MSP integration)
- `2`: Map AUX channels to power level control only
- `3`: Map AUX channels to band and channel control only
- `4`: Map AUX channels to all settings (power, band, and channel)
### Configuring AUX Map Entries
Use the following command format to add mapping entries:
```
vtxtable <index> <aux_channel> <band> <channel> <power> <start_pwm> <end_pwm>
```
Параметри:
- `index`: Map entry index (0-159)
- `aux_channel`: AUX channel number (3-19, where AUX1=3)
- `band`: Target band (1-24, or 0 to leave unchanged)
- `channel`: Target channel (1-16, or 0 to leave unchanged)
- `power`: Power level (1-16, 0 to leave unchanged, or -1 for pit mode)
- `start_pwm`: Start of PWM range in microseconds (typically 900-2100)
- `end_pwm`: End of PWM range in microseconds (typically 900-2100)
:::info
AUX channel numbering starts from 3 (AUX1=channel 3) to account for the first four RC channels 0-3 used for flight control.
:::
Example configuration for a 6-position dial controlling band/channel on AUX4 (channel 7):
```
vtx 0 7 7 1 0 900 1025
vtx 1 7 7 2 0 1025 1100
vtx 2 7 7 4 0 1100 1175
vtx 3 7 7 6 0 1175 1225
vtx 4 7 7 8 0 1225 1300
vtx 5 7 3 8 0 1300 2100
```
Example configuration for power control on AUX3 (channel 6):
```
vtxtable 16 6 0 0 -1 900 1250
vtxtable 17 6 0 0 1 1250 1525
vtxtable 18 6 0 0 2 1525 1650
vtxtable 19 6 0 0 3 1650 1875
vtxtable 20 6 0 0 4 1875 2010
```
Save the configuration with:
```
vtxtable save
```
The map status can be verified with `vtxtable status`.
## CRSF MSP Integration
When using a CRSF receiver with MSP support, you can control VTX settings directly from your transmitter using MSP commands sent over the CRSF link.
This feature must be enabled at compile time with the `VTX_CRSF_MSP_SUPPORT` Kconfig option.
To enable CRSF MSP control, set `VTX_MAP_CONFIG` to one of:
- `1`: MSP controls both frequency (band/channel) and power
- `2`: MSP controls frequency (band/channel) only, AUX controls power
- `3`: MSP controls power only, AUX controls band/channel
When MSP integration is active, the driver responds to `MSP_SET_VTX_CONFIG` (0x59) commands.
The transmitter can send band, channel, frequency, power level, and pit mode settings via MSP, which are automatically mapped to the corresponding PX4 parameters.
:::tip
The MSP integration allows seamless VTX control from transmitters that support VTX configuration via Lua scripts or built-in VTX menus without requiring additional hardware switches.
:::
## Build Configuration
Both the VTX driver and VTX table support are configured via Kconfig options.
Key configuration options:
- `VTX_CRSF_MSP_SUPPORT`: Enables CRSF MSP command support (default: disabled)
- `VTXTABLE_CONFIG_FILE`: File path for persistent configuration (default: `/fs/microsd/vtx_config`)
- `VTXTABLE_AUX_MAP`: Enables AUX channel mapping (default: disabled)
## Parameter Reference
### VTX Settings Parameters
- `VTX_BAND` (0-23): Frequency band selection (Band 1-24 in UI)
- `VTX_CHANNEL` (0-15): Channel within band (Channel 1-16 in UI)
- `VTX_FREQUENCY` (0-32000): Direct frequency in MHz (overrides band/channel when non-zero)
- `VTX_POWER` (0-15): Power level (Level 1-16 in UI, as configured in table)
- `VTX_PIT_MODE` (boolean): Pit mode for reduced power (default: disabled)
### Налаштування параметрів
- `VTX_SER_CFG`: Serial port assignment for VTX communication
- `VTX_MAP_CONFIG`: Controls how VTX settings are mapped:
- Without `VTX_CRSF_MSP_SUPPORT`:
- `0`: Disabled
- `1`: Disabled
- `2`: AUX controls power only
- `3`: AUX controls band/channel only
- `4`: AUX controls both power and band/channel
- With `VTX_CRSF_MSP_SUPPORT`:
- `0`: Disabled
- `1`: MSP controls both frequency and power
- `2`: MSP controls frequency, AUX controls power
- `3`: MSP controls power, AUX controls band/channel
- `4`: Not used with MSP support
- `VTX_DEVICE`: Device-specific configuration (see below)
## Device-Specific Configuration
The `VTX_DEVICE` parameter allows device-specific workarounds.
It encodes both the protocol type and device variant:
- Low byte (bits 0-7): Protocol selection
- `0`: SmartAudio (default)
- `1`: Tramp
- High byte (bits 8-15): Device-specific variant
- `0`: Generic device
- `20`: Peak THOR T67
- `40`: Rush Max Solo
### Known Device Workarounds
**Peak THOR T67** (`VTX_DEVICE` = 5120):
This device incorrectly reports pit mode status but otherwise functions normally.
The driver applies a workaround to override the reported status with the actual configured state.
For generic devices, use `VTX_DEVICE` = 0 (SmartAudio) or `VTX_DEVICE` = 1 (Tramp).
-3
View File
@@ -93,7 +93,6 @@
- [VTOL后转换调参](config_vtol/vtol_back_transition_tuning.md)
- [没有空速传感器的VTOL ](config_vtol/vtol_without_airspeed_sensor.md)
- [垂直起降风向仪](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)
@@ -362,8 +361,6 @@
- [Satellite Comms (Iridium/RockBlock)](advanced_features/satcom_roadblock.md)
- [Analog Video Transmitters](vtx/index.md)
- [Power Systems](power_systems/index.md)
- [Battery Estimation Tuning](config/battery.md)
- [Battery Chemistry Overview](power_systems/battery_chemistry.md)
+1 -1
View File
@@ -106,7 +106,7 @@ The settings and underlying parameters are shown below.
| 设置 | 参数 | 描述 |
| -------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <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_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_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
-1
View File
@@ -9,4 +9,3 @@ Then perform VTOL-specific configuration and tuning:
- [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)
-22
View File
@@ -1,22 +0,0 @@
# 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
:::
+1 -1
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 140 characters.
- Maximum line length is 120 characters.
### File Extensions
+1 -5
View File
@@ -89,19 +89,15 @@ 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/).
:::
3. Create and open a new _cmake_ definition file named **CMakeLists.txt**.
@@ -170,7 +166,7 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too
4. 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)).
复制下面的文本:
```text
```
menuconfig EXAMPLES_PX4_SIMPLE_APP
bool "px4_simple_app"
default n
+1 -1
View File
@@ -35,7 +35,7 @@ Source: [modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/mod
This module implements the MAVLink protocol, which can be used on a Serial link or UDP network connection. It communicates with the system via uORB: some messages are directly handled in the module (eg. mission protocol), others are published via uORB (eg. vehicle_command).
流(Stream)被用来以特定速率发送周期性的消息,例如飞机姿态信息。
When starting the mavlink instance, a mode can be specified, which defines the set of enabled streams with their rates.
Streams are used to send periodic messages with a specific rate, such as the vehicle attitude. When starting the mavlink instance, a mode can be specified, which defines the set of enabled streams with their rates. For a running instance, streams can be configured via <code>mavlink stream</code> command.
For a running instance, streams can be configured via `mavlink stream` command.
可以存在多个该模块的实例,每个实例连接到一个串口设备或者网络端口。
@@ -22,11 +22,7 @@ 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.
:::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 .
:::
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
+1 -1
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://raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
<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).
+1 -1
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://www.flarm.com/en/drones/)
- [FLARM](https://flarm.com/products/uav/atom-uav-flarm-for-drones/) <!-- I think originally https://flarm.com/products/powerflarm/uav/ -->
## 硬件安装
+1 -7
View File
@@ -14,7 +14,7 @@ Experimental
:::
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.
[PX4 ROS 2接口库](../ros2/px4_ros2_interface_lib.md)是一个 C++ 库,可简化从 ROS 2 控制 PX4 的操作。
开发者可使用该库创建并动态注册以 ROS 2 编写的模式。
这些模式会动态注册到 PX4 中,并且对于地面站或其他外部系统而言,它们看起来就像是 PX4 的一部分。
@@ -26,12 +26,6 @@ The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ li
PX4 ROS 2 模式相较于 PX4 内部模式,更易于实现和维护,并且在处理能力与既有代码库资源方面,能为开发者提供更丰富的支持。
除非该模式属于安全关键型、对时序有严格要求或需要极高的更新速率,或者你的飞行器没有搭载伴随计算机,否则你应优先[考虑使用 PX4 ROS 2 模式,而非 PX4 内部模式](../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://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_py/src/px4_ros2).
You are welcome to add and contribute missing classes.
:::
## 综述
该图从概念层面概述了控制接口模式与模式执行器如何与 PX4 进行交互。
+1 -1
View File
@@ -7,7 +7,7 @@ Experimental
在撰写本文时,PX4 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.
[PX4 ROS 2 接口库 ]https://github.com/Auterion/px4-ros2-interface-lib)是一个 C++ 库,可简化从 ROS 2 对 PX4 进行控制和交互的操作。
该库为开发者提供了两个高级接口。
-287
View File
@@ -1,287 +0,0 @@
# Analog Video Transmitters
Analog Video Transmitters (VTX) can be controlled by PX4 via a half-duplex UART connection implementing the SmartAudio v1, v2, and v2.1 and Tramp protocols.
The protocols allow writing and reading:
- device status.
- transmission frequency in MHz or via band and channel index.
- transmission power in dBm or mW.
- operation modes.
VTX settings are controlled by parameters and optionally via RC AUX channels or CRSF MSP commands.
The driver stores frequency and power tables that map band/channel indices to actual transmission values.
Configuration is device-specific and set up using the command line interface.
## 入门指南
Connect the SmartAudio or Tramp pin of the VTX to the TX pin of a free serial port on the flight controller.
Then set the following parameters:
- `VTX_SER_CFG`: Select the serial port used for VTX communication.
- `VTX_DEVICE`: Selects the VTX device (generic SmartAudio/Tramp or a specific device).
Note that since the VTX communication is half-duplex, you can, for example, use the single-pin Radio Controller port for the VTX and use a full duplex TELEM port for CRSF communication.
You should now be able to see the VTX device in the driver status:
```
nsh> vtx status
INFO [vtx] UART device: /dev/ttyS4
INFO [vtx] VTX table "UNINITIALIZED":
INFO [vtx] Power levels:
INFO [vtx] RC mapping: Disabled
INFO [vtx] Parameters:
INFO [vtx] band: 1
INFO [vtx] channel: 1
INFO [vtx] frequency: 0 MHz
INFO [vtx] power level: 1
INFO [vtx] power: 0 = 0 mW
INFO [vtx] pit mode: off
INFO [vtx] SmartAudio v2:
INFO [vtx] band: 1
INFO [vtx] channel: 1
INFO [vtx] frequency: 6110 MHz
INFO [vtx] power level: 1
INFO [vtx] power: 0 mW
INFO [vtx] pit mode: on
INFO [vtx] lock: unlocked
```
:::warning
Without a configured power table, power mappings are unknown and default to 0 mW.
Some VTX devices enter pit mode when power is set to 0, regardless of the `VTX_PIT_MODE` parameter.
:::
## VTX Table Configuration
The VTX table stores frequency and power mappings for your specific device.
The manufacturer usually provides this information in the form of a JSON file that can be translated into a [Betaflight CLI command set](https://www.betaflight.com/docs/development/VTX#vtx-table) that this driver implements for compatibility.
### Power Level Configuration
```
# Set table name ≤16 characters
vtxtable name "Peak THOR T67"
# Set the power values that are sent to the VTX for each power level index
# Note: SmartAudio v1 and v2 use index values!
vtxtable powervalues 0 1 2 3 4
# Note: SmartAudio v2.1 uses dBm values instead!
# vtxtable powervalues 14 23 27 30 35
# Note: Tramp uses mW values instead!
# vtxtable powervalues 25 200 500 1000 3000
# Set the corresponding power labels for each power level index ≤4 characters.
# These are used for status reporting.
vtxtable powerlabels 25 200 500 1W 3W
# Set number of power levels
vtxtable powerlevels 5
# Save configuration
vtxtable save
```
This will create a VTX table with 5 power levels.
```nsh> vtxtable status
INFO [vtxtable] VTX table "Peak THOR T67":
INFO [vtxtable] Power levels:
INFO [vtxtable] 1: 0 = 25
INFO [vtxtable] 2: 1 = 200
INFO [vtxtable] 3: 2 = 500
INFO [vtxtable] 4: 3 = 1W
INFO [vtxtable] 5: 4 = 3W
```
### Frequency Table Configuration
```
# Set the name of each band and the frequencies of each channel
vtxtable band 1 BAND_A A FACTORY 6110 6130 6150 6170 6190 6210 6230 6250
vtxtable band 2 BAND_B B FACTORY 6270 6290 6310 6330 6350 6370 6390 6410
vtxtable band 3 BAND_E E FACTORY 6430 6450 6470 6490 6510 6530 6550 6570
vtxtable band 4 BAND_F F FACTORY 6590 6610 6630 6650 6670 6690 6710 6730
vtxtable band 5 BAND_R R FACTORY 6750 6770 6790 6810 6830 6850 6870 6890
vtxtable band 6 BAND_P P FACTORY 6910 6930 6950 6970 6990 7010 7030 7050
vtxtable band 7 BAND_H H FACTORY 7070 7090 7110 7130 7150 7170 7190 7210
vtxtable band 8 BAND_U U FACTORY 6115 6265 6425 6585 6745 6905 7065 7185
# Set number of bands and channels
vtxtable bands 8
vtxtable channels 8
# Save configuration
vtxtable save
```
This will create a VTX table with 8 bands and 8 channels.
Note that FACTORY sends the band and channel indexes to the VTX device and they use their internal frequency mapping. In this mode the frequency is just for indication purposes.
In contrast, CUSTOM would send the actual frequency values to the VTX device, but not all devices support this mode.
Setting a frequency to zero will skip setting it.
```
nsh> vtxtable status
INFO [vtxtable] VTX table 8x8: Peak THOR T67
INFO [vtxtable] A: BAND_A = 6110 6130 6150 6170 6190 6210 6230 6250
INFO [vtxtable] B: BAND_B = 6270 6290 6310 6330 6350 6370 6390 6410
INFO [vtxtable] E: BAND_E = 6430 6450 6470 6490 6510 6530 6550 6570
INFO [vtxtable] F: BAND_F = 6590 6610 6630 6650 6670 6690 6710 6730
INFO [vtxtable] R: BAND_R = 6750 6770 6790 6810 6830 6850 6870 6890
INFO [vtxtable] P: BAND_P = 6910 6930 6950 6970 6990 7010 7030 7050
INFO [vtxtable] H: BAND_H = 7070 7090 7110 7130 7150 7170 7190 7210
INFO [vtxtable] U: BAND_U = 6115 6265 6425 6585 6745 6905 7065 7185
```
### Table Constraints
Maximum table dimensions:
- ≤24 bands each with ≤16 channels and ≤32GHz frequency values.
- ≤16 power levels.
- ≤16 characters table name.
- ≤12 characters band name and 1 character band letter.
- ≤4 characters power label length (to support "2.5W").
## AUX Channel Mapping
The AUX mapping feature allows you to control VTX settings using RC AUX channels.
Each mapping entry defines an AUX channel range that triggers a specific VTX configuration.
To enable AUX mapping, set `VTX_MAP_CONFIG` to one of the following values:
- `0`: Disabled
- `1`: Disabled (reserved for CRSF MSP integration)
- `2`: Map AUX channels to power level control only
- `3`: Map AUX channels to band and channel control only
- `4`: Map AUX channels to all settings (power, band, and channel)
### Configuring AUX Map Entries
Use the following command format to add mapping entries:
```
vtxtable <index> <aux_channel> <band> <channel> <power> <start_pwm> <end_pwm>
```
Parameters:
- `index`: Map entry index (0-159)
- `aux_channel`: AUX channel number (3-19, where AUX1=3)
- `band`: Target band (1-24, or 0 to leave unchanged)
- `channel`: Target channel (1-16, or 0 to leave unchanged)
- `power`: Power level (1-16, 0 to leave unchanged, or -1 for pit mode)
- `start_pwm`: Start of PWM range in microseconds (typically 900-2100)
- `end_pwm`: End of PWM range in microseconds (typically 900-2100)
:::info
AUX channel numbering starts from 3 (AUX1=channel 3) to account for the first four RC channels 0-3 used for flight control.
:::
Example configuration for a 6-position dial controlling band/channel on AUX4 (channel 7):
```
vtx 0 7 7 1 0 900 1025
vtx 1 7 7 2 0 1025 1100
vtx 2 7 7 4 0 1100 1175
vtx 3 7 7 6 0 1175 1225
vtx 4 7 7 8 0 1225 1300
vtx 5 7 3 8 0 1300 2100
```
Example configuration for power control on AUX3 (channel 6):
```
vtxtable 16 6 0 0 -1 900 1250
vtxtable 17 6 0 0 1 1250 1525
vtxtable 18 6 0 0 2 1525 1650
vtxtable 19 6 0 0 3 1650 1875
vtxtable 20 6 0 0 4 1875 2010
```
Save the configuration with:
```
vtxtable save
```
The map status can be verified with `vtxtable status`.
## CRSF MSP Integration
When using a CRSF receiver with MSP support, you can control VTX settings directly from your transmitter using MSP commands sent over the CRSF link.
This feature must be enabled at compile time with the `VTX_CRSF_MSP_SUPPORT` Kconfig option.
To enable CRSF MSP control, set `VTX_MAP_CONFIG` to one of:
- `1`: MSP controls both frequency (band/channel) and power
- `2`: MSP controls frequency (band/channel) only, AUX controls power
- `3`: MSP controls power only, AUX controls band/channel
When MSP integration is active, the driver responds to `MSP_SET_VTX_CONFIG` (0x59) commands.
The transmitter can send band, channel, frequency, power level, and pit mode settings via MSP, which are automatically mapped to the corresponding PX4 parameters.
:::tip
The MSP integration allows seamless VTX control from transmitters that support VTX configuration via Lua scripts or built-in VTX menus without requiring additional hardware switches.
:::
## Build Configuration
Both the VTX driver and VTX table support are configured via Kconfig options.
Key configuration options:
- `VTX_CRSF_MSP_SUPPORT`: Enables CRSF MSP command support (default: disabled)
- `VTXTABLE_CONFIG_FILE`: File path for persistent configuration (default: `/fs/microsd/vtx_config`)
- `VTXTABLE_AUX_MAP`: Enables AUX channel mapping (default: disabled)
## Parameter Reference
### VTX Settings Parameters
- `VTX_BAND` (0-23): Frequency band selection (Band 1-24 in UI)
- `VTX_CHANNEL` (0-15): Channel within band (Channel 1-16 in UI)
- `VTX_FREQUENCY` (0-32000): Direct frequency in MHz (overrides band/channel when non-zero)
- `VTX_POWER` (0-15): Power level (Level 1-16 in UI, as configured in table)
- `VTX_PIT_MODE` (boolean): Pit mode for reduced power (default: disabled)
### Configuration Parameters
- `VTX_SER_CFG`: Serial port assignment for VTX communication
- `VTX_MAP_CONFIG`: Controls how VTX settings are mapped:
- Without `VTX_CRSF_MSP_SUPPORT`:
- `0`: Disabled
- `1`: Disabled
- `2`: AUX controls power only
- `3`: AUX controls band/channel only
- `4`: AUX controls both power and band/channel
- With `VTX_CRSF_MSP_SUPPORT`:
- `0`: Disabled
- `1`: MSP controls both frequency and power
- `2`: MSP controls frequency, AUX controls power
- `3`: MSP controls power, AUX controls band/channel
- `4`: Not used with MSP support
- `VTX_DEVICE`: Device-specific configuration (see below)
## Device-Specific Configuration
The `VTX_DEVICE` parameter allows device-specific workarounds.
It encodes both the protocol type and device variant:
- Low byte (bits 0-7): Protocol selection
- `0`: SmartAudio (default)
- `1`: Tramp
- High byte (bits 8-15): Device-specific variant
- `0`: Generic device
- `20`: Peak THOR T67
- `40`: Rush Max Solo
### Known Device Workarounds
**Peak THOR T67** (`VTX_DEVICE` = 5120):
This device incorrectly reports pit mode status but otherwise functions normally.
The driver applies a workaround to override the reported status with the actual configured state.
For generic devices, use `VTX_DEVICE` = 0 (SmartAudio) or `VTX_DEVICE` = 1 (Tramp).
+1 -1
View File
@@ -20,4 +20,4 @@ uint8 payload_length # Length of the data transported in payload
uint8[128] payload # Data itself
# Topic aliases for known payload types
# TOPICS mavlink_tunnel esc_serial_passthru io_serial_passthru
# TOPICS mavlink_tunnel esc_serial_passthru
-2
View File
@@ -2,7 +2,6 @@
#include <px4_platform_common/time.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/log.h>
#include <uORB/uORB.h>
#include "apps.h"
@@ -44,7 +43,6 @@ void list_builtins(apps_map_type &apps)
int shutdown_main(int argc, char *argv[])
{
printf("Exiting NOW.\n");
uorb_shutdown();
system_exit(0);
}
-3
View File
@@ -49,7 +49,6 @@
#include <px4_platform_common/external_reset_lockout.h>
#include <px4_platform_common/log.h>
#include <uORB/uORB.h>
#include <stdint.h>
#include <errno.h>
@@ -174,8 +173,6 @@ static void shutdown_worker(void *arg)
const bool delay_elapsed = (now > shutdown_time_us);
if (delay_elapsed && ((done && shutdown_lock_counter == 0) || (now > (shutdown_time_us + shutdown_timeout_us)))) {
uorb_shutdown();
if (shutdown_args & SHUTDOWN_ARG_REBOOT) {
#if defined(CONFIG_BOARDCTL_RESET)
PX4_INFO_RAW("Reboot NOW.");
-13
View File
@@ -51,7 +51,6 @@
#include <sys/boardctl.h>
#endif
static uORB::DeviceMaster *g_dev = nullptr;
int uorb_start(void)
@@ -114,18 +113,6 @@ int uorb_top(char **topic_filter, int num_filters)
return OK;
}
void uorb_shutdown(void)
{
#ifdef CONFIG_ORB_COMMUNICATOR
uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator();
if (ch) {
ch->shutdown();
}
#endif /* CONFIG_ORB_COMMUNICATOR */
}
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)
{
return uORB::Manager::get_instance()->orb_advertise(meta, data);
-1
View File
@@ -121,7 +121,6 @@ __BEGIN_DECLS
int uorb_start(void);
int uorb_status(void);
int uorb_top(char **topic_filter, int num_filters);
void uorb_shutdown(void);
/**
* ORB topic advertiser handle.
@@ -129,22 +129,6 @@ public:
virtual int16_t send_message(const char *messageName, int32_t length, uint8_t *data) = 0;
//=========================================================================
// INTERFACES FOR Lifecycle messages
//=========================================================================
/**
* @brief Interface to notify the remote entity of a shutdown.
*
* @return
* 0 = success; This means the shutdown is successfully sent to the receiver
* Note: This does not mean that the receiver has received it.
* otherwise = failure.
*/
virtual int16_t shutdown() { return 0; }
};
/**
+25 -15
View File
@@ -51,7 +51,7 @@
#include <errno.h>
#include "hrt_work.h"
// Voxl board specific API definitions to get time
// Voxl2 board specific API definitions to get time offset
#if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
#include "fc_sensor.h"
#endif
@@ -112,6 +112,29 @@ hrt_abstime hrt_absolute_time()
#else // defined(ENABLE_LOCKSTEP_SCHEDULER)
struct timespec ts;
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
# if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
hrt_abstime temp_abstime = ts_to_abstime(&ts);
int apps_time_offset = fc_sensor_get_time_offset();
if (apps_time_offset < 0) {
hrt_abstime temp_offset = -apps_time_offset;
if (temp_offset >= temp_abstime) {
temp_abstime = 0;
} else {
temp_abstime -= temp_offset;
}
} else {
temp_abstime += (hrt_abstime) apps_time_offset;
}
ts.tv_sec = temp_abstime / 1000000;
ts.tv_nsec = (temp_abstime % 1000000) * 1000;
# endif // defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
return ts_to_abstime(&ts);
#endif // defined(ENABLE_LOCKSTEP_SCHEDULER)
}
@@ -453,21 +476,8 @@ int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
}
#endif // defined(ENABLE_LOCKSTEP_SCHEDULER)
return system_clock_gettime(clk_id, tp);
int rv = system_clock_gettime(clk_id, tp);
# if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
// On VOXL use DSP clock as reference for MONOTONIC
if (clk_id == CLOCK_MONOTONIC) {
hrt_abstime temp_abstime = fc_sensor_get_dsp_timestamp_us();
tp->tv_sec = temp_abstime / 1000000;
tp->tv_nsec = (temp_abstime % 1000000) * 1000;
}
# endif // defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
return rv;
}
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
-2
View File
@@ -73,7 +73,6 @@
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/posix.h>
#include <uORB/uORB.h>
#include "apps.h"
#include "px4_daemon/client.h"
@@ -506,7 +505,6 @@ void sig_int_handler(int sig_num)
fflush(stdout);
printf("\nPX4 Exiting...\n");
fflush(stdout);
uorb_shutdown();
px4_daemon::Pxh::stop();
_exit_requested = true;
}
@@ -19,10 +19,6 @@ actuator_output:
label: 'ESC 3 Spin Direction'
- param: 'VOXL_ESC_SDIR4'
label: 'ESC 4 Spin Direction'
- param: 'VOXL_ESC_CMD'
label: 'ESC Command Type'
- param: 'VOXL_ESC_PWR_MIN'
label: 'ESC Minimum Power With PWM Command Type'
output_groups:
- param_prefix: VOXL_ESC
group_label: 'ESCs'
+39 -109
View File
@@ -300,7 +300,6 @@ int VoxlEsc::load_params(voxl_esc_params_t *params, ch_assign_t *map)
param_get(param_find("VOXL_ESC_SDIR3"), &params->direction_map[2]);
param_get(param_find("VOXL_ESC_SDIR4"), &params->direction_map[3]);
param_get(param_find("VOXL_ESC_PWR_MIN"), &params->pwr_min);
param_get(param_find("VOXL_ESC_RPM_MIN"), &params->rpm_min);
param_get(param_find("VOXL_ESC_RPM_MAX"), &params->rpm_max);
@@ -312,23 +311,10 @@ int VoxlEsc::load_params(voxl_esc_params_t *params, ch_assign_t *map)
param_get(param_find("VOXL_ESC_GPIO_CH"), &params->gpio_ctl_channel);
param_get(param_find("VOXL_ESC_CMD"), &params->cmd_type);
if (params->cmd_type > VOXL_ESC_PWM_CMDS) {
PX4_WARN("Warning, VOXL_ESC_CMD set to invalid value %d. Using 1 instead", (int) params->cmd_type);
params->cmd_type = VOXL_ESC_PWM_CMDS;
} else if (params->cmd_type < VOXL_ESC_RPM_CMDS) {
PX4_WARN("Warning, VOXL_ESC_CMD set to invalid value %d. Using 0 instead", (int) params->cmd_type);
params->cmd_type = VOXL_ESC_RPM_CMDS;
}
if (params->cmd_type == VOXL_ESC_RPM_CMDS) {
if (params->rpm_min >= params->rpm_max) {
PX4_ERR("Invalid parameter VOXL_ESC_RPM_MIN. Please verify parameters.");
params->rpm_min = 0;
ret = PX4_ERROR;
}
if (params->rpm_min >= params->rpm_max) {
PX4_ERR("Invalid parameter VOXL_ESC_RPM_MIN. Please verify parameters.");
params->rpm_min = 0;
ret = PX4_ERROR;
}
if (params->turtle_motor_percent < 0 || params->turtle_motor_percent > 100) {
@@ -406,24 +392,19 @@ int VoxlEsc::task_spawn(int argc, char *argv[])
int ch;
const char *myoptarg = nullptr;
VoxlEsc *instance = new VoxlEsc();
while ((ch = px4_getopt(argc, argv, "dv", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'd':
_device = argv[myoptind];
break;
// Parse any passed in options
if ((argc > 1) && (argv[1] != nullptr)) {
while ((ch = px4_getopt(argc - 1, &argv[1], "d:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'd':
_device = argv[myoptind];
PX4_INFO("Configuring device as %s", _device);
break;
default:
PX4_ERR("Unknown option: %c", ch);
break;
}
default:
break;
}
}
VoxlEsc *instance = new VoxlEsc();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
@@ -590,8 +571,6 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback)
QC_ESC_FB_POWER_STATUS packet;
memcpy(&packet, _fb_packet.buffer, packet_size);
_rx_power_status_count++;
float voltage = packet.voltage * 0.001f; // Voltage is reported at 1 mV resolution
float current = packet.current * 0.008f; // Total current is reported at 8mA resolution
@@ -928,19 +907,8 @@ int VoxlEsc::update_params()
if (ret == PX4_OK) {
_mixing_output.setAllDisarmedValues(0);
_mixing_output.setAllFailsafeValues(0);
if (_parameters.cmd_type == VOXL_ESC_RPM_CMDS) {
_mixing_output.setAllMinValues(_parameters.rpm_min);
_mixing_output.setAllMaxValues(_parameters.rpm_max);
} else if (_parameters.cmd_type == VOXL_ESC_PWM_CMDS) {
// we use a minimum value of 1, since 0 is for disarmed
_min_active_pwm = math::constrain(static_cast<int>((_parameters.pwr_min *
static_cast<float>(VOXL_ESC_PWM_MAX))),
VOXL_ESC_PWM_MIN, VOXL_ESC_PWM_MAX);
_mixing_output.setAllMinValues(_min_active_pwm);
_mixing_output.setAllMaxValues(VOXL_ESC_PWM_MAX);
}
_mixing_output.setAllMinValues(_parameters.rpm_min);
_mixing_output.setAllMaxValues(_parameters.rpm_max);
_rpm_fullscale = _parameters.rpm_max - _parameters.rpm_min;
}
@@ -1248,18 +1216,11 @@ bool VoxlEsc::updateOutputs(uint16_t outputs[MAX_ACTUATORS],
_esc_chans[i].rate_req = 0;
} else {
if ((_turtle_mode_en) || (_parameters.cmd_type == VOXL_ESC_RPM_CMDS)) {
if (_extended_rpm) {
if (outputs[i] > VOXL_ESC_RPM_MAX_EXT) { outputs[i] = VOXL_ESC_RPM_MAX_EXT; }
if (_extended_rpm) {
if (outputs[i] > VOXL_ESC_RPM_MAX_EXT) { outputs[i] = VOXL_ESC_RPM_MAX_EXT; }
} else {
if (outputs[i] > VOXL_ESC_RPM_MAX) { outputs[i] = VOXL_ESC_RPM_MAX; }
}
} else if (_parameters.cmd_type == VOXL_ESC_PWM_CMDS) {
if (outputs[i] > VOXL_ESC_PWM_MAX) { outputs[i] = VOXL_ESC_PWM_MAX; }
else if (outputs[i] < _min_active_pwm) { outputs[i] = _min_active_pwm; }
} else {
if (outputs[i] > VOXL_ESC_RPM_MAX) { outputs[i] = VOXL_ESC_RPM_MAX; }
}
if (!_turtle_mode_en) {
@@ -1274,34 +1235,18 @@ bool VoxlEsc::updateOutputs(uint16_t outputs[MAX_ACTUATORS],
Command cmd;
if (_parameters.cmd_type == VOXL_ESC_RPM_CMDS) {
cmd.len = qc_esc_create_rpm_packet4_fb(_esc_chans[0].rate_req,
_esc_chans[1].rate_req,
_esc_chans[2].rate_req,
_esc_chans[3].rate_req,
_esc_chans[0].led,
_esc_chans[1].led,
_esc_chans[2].led,
_esc_chans[3].led,
_fb_idx,
cmd.buf,
sizeof(cmd.buf),
_extended_rpm);
} else if (_parameters.cmd_type == VOXL_ESC_PWM_CMDS) {
cmd.len = qc_esc_create_pwm_packet4_fb(_esc_chans[0].rate_req,
_esc_chans[1].rate_req,
_esc_chans[2].rate_req,
_esc_chans[3].rate_req,
_esc_chans[0].led,
_esc_chans[1].led,
_esc_chans[2].led,
_esc_chans[3].led,
_fb_idx,
cmd.buf,
sizeof(cmd.buf));
}
cmd.len = qc_esc_create_rpm_packet4_fb(_esc_chans[0].rate_req,
_esc_chans[1].rate_req,
_esc_chans[2].rate_req,
_esc_chans[3].rate_req,
_esc_chans[0].led,
_esc_chans[1].led,
_esc_chans[2].led,
_esc_chans[3].led,
_fb_idx,
cmd.buf,
sizeof(cmd.buf),
_extended_rpm);
if (_uart_port.write(cmd.buf, cmd.len) != cmd.len) {
PX4_ERR("Failed to send packet");
@@ -1391,22 +1336,16 @@ bool VoxlEsc::updateOutputs(uint16_t outputs[MAX_ACTUATORS],
uint8_t num_writes = 0;
// Don't do these faster than 20Hz
if (hrt_elapsed_time(&_last_uart_passthru) > 50_ms) {
_last_uart_passthru = hrt_absolute_time();
while (_esc_serial_passthru_sub.updated() && (num_writes < 4)) {
mavlink_tunnel_s uart_passthru{};
_esc_serial_passthru_sub.copy(&uart_passthru);
// Don't do more than a few writes each check
while (_esc_serial_passthru_sub.updated() && (num_writes < 4)) {
mavlink_tunnel_s uart_passthru{};
_esc_serial_passthru_sub.copy(&uart_passthru);
if (_uart_port.write(uart_passthru.payload, uart_passthru.payload_length) != uart_passthru.payload_length) {
PX4_ERR("Failed to send mavlink tunnel data to esc");
return false;
}
num_writes++;
if (_uart_port.write(uart_passthru.payload, uart_passthru.payload_length) != uart_passthru.payload_length) {
PX4_ERR("Failed to send mavlink tunnel data to esc");
return false;
}
num_writes++;
}
perf_count(_output_update_perf);
@@ -1686,8 +1625,6 @@ void VoxlEsc::print_params()
PX4_INFO("Params: VOXL_ESC_SDIR3: %" PRId32, _parameters.direction_map[2]);
PX4_INFO("Params: VOXL_ESC_SDIR4: %" PRId32, _parameters.direction_map[3]);
PX4_INFO("Params: VOXL_ESC_PWR_MIN: %f", (double) _parameters.pwr_min);
PX4_INFO("Params: VOXL_ESC_RPM_MIN: %" PRId32, _parameters.rpm_min);
PX4_INFO("Params: VOXL_ESC_RPM_MAX: %" PRId32, _parameters.rpm_max);
@@ -1704,8 +1641,6 @@ void VoxlEsc::print_params()
PX4_INFO("Params: VOXL_ESC_T_OVER: %" PRId32, _parameters.esc_over_temp_threshold);
PX4_INFO("Params: VOXL_ESC_GPIO_CH: %" PRId32, _parameters.gpio_ctl_channel);
PX4_INFO("Params: VOXL_ESC_CMD: %" PRId32, _parameters.cmd_type);
}
int VoxlEsc::print_status()
@@ -1715,10 +1650,6 @@ int VoxlEsc::print_status()
PX4_INFO("UART port: %s", _device);
PX4_INFO("UART open: %s", _uart_port.isOpen() ? "yes" : "no");
PX4_INFO("CRC error count: %lu", (long unsigned int) _rx_crc_error_count);
PX4_INFO("Packet RX count: %lu", (long unsigned int) _rx_packet_count);
PX4_INFO("Power status count: %lu", (long unsigned int) _rx_power_status_count);
PX4_INFO("");
print_params();
PX4_INFO("");
@@ -1758,7 +1689,6 @@ const char * VoxlEsc::board_id_to_name(int board_id)
case 40: return "ModalAi 4-in-1 ESC (M0129-3)";
case 41: return "ModalAi 4-in-1 ESC (M0134-6)";
case 42: return "ModalAi 4-in-1 ESC (M0138-1)";
case 44: return "ModalAi 4-in-1 ESC (M0129-6)";
default: return "Unknown Board";
}
}
+3 -12
View File
@@ -117,8 +117,8 @@ private:
static constexpr uint16_t DISARMED_VALUE = 0;
static constexpr int VOXL_ESC_PWM_MIN = 1;
static constexpr int VOXL_ESC_PWM_MAX = 800;
static constexpr uint16_t VOXL_ESC_PWM_MIN = 0;
static constexpr uint16_t VOXL_ESC_PWM_MAX = 800;
static constexpr uint16_t VOXL_ESC_DEFAULT_RPM_MIN = 5000;
static constexpr uint16_t VOXL_ESC_DEFAULT_RPM_MAX = 17000;
@@ -148,9 +148,6 @@ private:
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX5 = 5;
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX6 = 6;
static constexpr int32_t VOXL_ESC_RPM_CMDS = 0;
static constexpr int32_t VOXL_ESC_PWM_CMDS = 1;
Serial _uart_port{};
typedef struct {
@@ -162,7 +159,6 @@ private:
float turtle_stick_minf{0.15f};
float turtle_cosphi{0.99f};
int32_t baud_rate{VOXL_ESC_DEFAULT_BAUD};
float pwr_min{0.05f};
int32_t rpm_min{VOXL_ESC_DEFAULT_RPM_MIN};
int32_t rpm_max{VOXL_ESC_DEFAULT_RPM_MAX};
int32_t function_map[VOXL_ESC_OUTPUT_CHANNELS] {0, 0, 0, 0};
@@ -173,7 +169,6 @@ private:
int32_t esc_warn_temp_threshold{0};
int32_t esc_over_temp_threshold{0};
int32_t gpio_ctl_channel{0};
int32_t cmd_type{0};
} voxl_esc_params_t;
struct EscChan {
@@ -227,8 +222,6 @@ private:
bool _need_version_info{true};
QC_ESC_EXTENDED_VERSION_INFO _version_info[VOXL_ESC_OUTPUT_CHANNELS];
int _min_active_pwm{1};
voxl_esc_params_t _parameters;
int update_params();
int load_params(voxl_esc_params_t *params, ch_assign_t *map);
@@ -257,15 +250,13 @@ private:
int _fb_idx;
uint32_t _rx_crc_error_count{0};
uint32_t _rx_packet_count{0};
uint32_t _rx_power_status_count{0};
static const uint8_t READ_BUF_SIZE = 128;
uint8_t _read_buf[READ_BUF_SIZE];
Battery _battery;
static constexpr unsigned _battery_report_interval{20_ms};
static constexpr unsigned _battery_report_interval{100_ms};
hrt_abstime _last_battery_report_time;
hrt_abstime _last_uart_passthru{0};
bool _device_initialized{false};
@@ -276,31 +276,3 @@ PARAM_DEFINE_INT32(VOXL_ESC_T_OVER, 0);
* @max 6
*/
PARAM_DEFINE_INT32(VOXL_ESC_GPIO_CH, 0);
/**
* UART ESC command type
*
* Selects between RPM or PWM commands
*
* @reboot_required true
*
* @group VOXL ESC
* @value 0 - RPM
* @value 1 - PWM
* @min 0
* @max 1
*/
PARAM_DEFINE_INT32(VOXL_ESC_CMD, 0);
/**
* UART ESC Minimum motor power
*
* Minimum motor power for ESC when VOXL_ESC_CMD is set for PWM.
* Make sure to set this high enough so that the motors are always spinning
* while armed.
*
* @group VOXL ESC
* @min 0.0
* @max 1.0
*/
PARAM_DEFINE_FLOAT(VOXL_ESC_PWR_MIN, 0.05);
@@ -107,12 +107,6 @@ private:
ZeroOffset = 116,
};
enum class RegisterGRF : uint8_t {
DistanceOutput = 27,
UpdateRate = 74,
};
static constexpr uint16_t output_data_config_sf20 = 0b110'1011'0100;
static constexpr uint8_t output_data_config_sf30 = 0b0111'1110;
@@ -129,7 +123,6 @@ private:
Generic = 0,
LW20c,
SF30d,
GRF,
};
enum class State {
Configuring,
@@ -249,20 +242,6 @@ int LightwareLaser::init()
_type = Type::SF30d;
break;
case 8: /* GRF250 (250m 5Hz) */
_px4_rangefinder.set_min_distance(0.1f);
_px4_rangefinder.set_max_distance(250.0f);
_conversion_interval = 200000;
_type = Type::GRF;
break;
case 9: /* GRF500 (500m 5Hz) */
_px4_rangefinder.set_min_distance(0.1f);
_px4_rangefinder.set_max_distance(500.0f);
_conversion_interval = 200000;
_type = Type::GRF;
break;
default:
PX4_ERR("invalid HW model %" PRId32 ".", hw_model);
return ret;
@@ -299,9 +278,6 @@ int LightwareLaser::probe()
case Type::SF30d:
return enableI2CBinaryProtocol("SF30", "LW30");
case Type::GRF:
return enableI2CBinaryProtocol("GRF250", "GRF500");
}
return -1;
@@ -385,17 +361,6 @@ int LightwareLaser::configure()
return ret;
}
break;
case Type::GRF: {
int ret = enableI2CBinaryProtocol("GRF250", "GRF500");
const uint8_t cmd1[] = {(uint8_t) RegisterGRF::UpdateRate, 0, 0, 0, 50};
ret |= transfer(cmd1, sizeof(cmd1), nullptr, 0);
uint8_t cmd2[] = {(uint8_t)RegisterGRF::DistanceOutput, 0, 0, 1};
ret |= transfer(cmd2, sizeof(cmd2), nullptr, 0);
return ret;
}
break;
}
return -1;
@@ -425,29 +390,6 @@ int LightwareLaser::collect()
break;
}
case Type::GRF: {
/* read from the sensor */
perf_begin(_sample_perf);
uint8_t val[4] {};
const hrt_abstime timestamp_sample = hrt_absolute_time();
if (readRegister((uint8_t)Register::DistanceData, &val[0], 4) < 0) {
perf_count(_comms_errors);
perf_end(_sample_perf);
PX4_INFO("Register Read Error");
return PX4_ERROR;
}
perf_end(_sample_perf);
uint16_t distance_cm = val[2] << 16 | val[1] << 8 | val[0];
float distance_m = float(distance_cm) * 1e-1f;
_px4_rangefinder.update(timestamp_sample, distance_m);
break;
}
case Type::LW20c:
case Type::SF30d:
@@ -474,8 +416,6 @@ int LightwareLaser::collect()
_px4_rangefinder.update(timestamp_sample, distance_m, quality);
break;
}
return PX4_OK;
@@ -558,10 +498,6 @@ int LightwareLaser::updateRestriction()
const uint8_t cmd[] = {(uint8_t)Register::LaserFiring, (uint8_t)(_restriction ? 0 : 1)};
return transfer(cmd, sizeof(cmd), nullptr, 0);
}
case Type::GRF: {
return 0;
}
}
}
@@ -36,7 +36,7 @@
*
* @reboot_required true
* @min 0
* @max 9
* @max 7
* @group Sensors
* @value 0 Disabled
* @value 1 SF10/a
@@ -46,8 +46,6 @@
* @value 5 SF/LW20/b
* @value 6 SF/LW20/c
* @value 7 SF/LW30/d
* @value 8 GRF250
* @value 9 GRF500
*/
PARAM_DEFINE_INT32(SENS_EN_SF1XX, 0);
-16
View File
@@ -786,13 +786,6 @@ GPS::run()
param_get(handle, &gps_ubx_min_elev);
}
int32_t gps_ubx_rate = 0;
handle = param_find("GPS_UBX_RATE");
if (handle != PARAM_INVALID) {
param_get(handle, &gps_ubx_rate);
}
handle = param_find("GPS_UBX_MODE");
GPSDriverUBX::UBXMode ubx_mode{GPSDriverUBX::UBXMode::Normal};
@@ -858,13 +851,6 @@ GPS::run()
param_get(handle, &ppk_output);
}
handle = param_find("GPS_UBX_JAM_DET");
int32_t jam_det_sensitivity_hi = 1;
if (handle != PARAM_INVALID) {
param_get(handle, &jam_det_sensitivity_hi);
}
int32_t gnssSystemsParam = static_cast<int32_t>(GPSHelper::GNSSSystemsMask::RECEIVER_DEFAULTS);
if (_instance == Instance::Main) {
@@ -952,11 +938,9 @@ GPS::run()
.dgnss_timeout = (uint8_t)gps_ubx_dgnss_to,
.min_cno = (uint8_t)gps_ubx_min_cno,
.min_elev = (int8_t)gps_ubx_min_elev,
.output_rate = (uint8_t)gps_ubx_rate,
.heading_offset = heading_offset,
.uart2_baudrate = f9p_uart2_baudrate,
.ppk_output = ppk_output > 0,
.jam_det_sensitivity_hi = jam_det_sensitivity_hi > 0,
.mode = ubx_mode,
};
-33
View File
@@ -114,25 +114,6 @@ PARAM_DEFINE_INT32(GPS_UBX_MIN_CNO, 0);
*/
PARAM_DEFINE_INT32(GPS_UBX_MIN_ELEV, 0);
/**
* u-blox GPS output rate
*
* Configure the output rate of u-blox GPS receivers (protocol v27+).
* When set to 0, automatic rate selection is used based on the receiver model.
* Default rates: M9N=8Hz, F9P L1L2=5Hz, F9P L1L5=5Hz, Others=10Hz.
*
* Note: Higher rates reduce satellite count (e.g., >8Hz limits to 16 SVs on M9N).
* Max rates vary by model and RTK mode: F9P L1L2=5-7Hz, F9P L1L5=7-8Hz, X20=25Hz.
* High rates at 115200 baud may cause dropouts.
*
* @min 0
* @max 25
* @unit Hz
* @reboot_required true
* @group GPS
*/
PARAM_DEFINE_INT32(GPS_UBX_RATE, 0);
/**
* Enable sat info (if available)
*
@@ -217,20 +198,6 @@ PARAM_DEFINE_INT32(GPS_UBX_CFG_INTF, 0);
*/
PARAM_DEFINE_INT32(GPS_UBX_PPK, 0);
/**
* u-blox GPS jamming detection high sensitivity mode
*
* Enables or disables the high sensitivity mode for the u-blox jamming detection
* (CFG-SEC-JAMDET_SENSITIVITY_HI). When enabled, the receiver uses a
* more sensitive algorithm to detect jamming. Disabling this may reduce false
* positives in electrically noisy environments.
*
* @boolean
* @reboot_required true
* @group GPS
*/
PARAM_DEFINE_INT32(GPS_UBX_JAM_DET, 1);
/**
* Wipes the flash config of UBX modules.
*
+1 -1
View File
@@ -110,7 +110,7 @@ private:
float measured_temperature = 0;
float measured_humidity = 0;
uint64_t measurement_time = 0;
uint32_t measurement_time = 0;
uint16_t measurement_index = 0;
sht_info _sht_info;
@@ -244,8 +244,6 @@ void QMC5883P::RunImpl()
bool QMC5883P::Configure()
{
RegisterWrite(Register::REG_29, 0x06);
// first set and clear all configured register bits
for (const auto &reg_cfg : _register_cfg) {
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
@@ -107,7 +107,7 @@ private:
static constexpr uint8_t size_register_cfg{2};
register_config_t _register_cfg[size_register_cfg] {
// Register | Set bits, Clear bits
{ Register::CNTL1, CNTL1_BIT::MODE_CONTINUOUS | CNTL1_BIT::OSR2_4 | CNTL1_BIT::ODR_200HZ, CNTL1_BIT::OSR1_8},
{ Register::CNTL1, CNTL1_BIT::MODE_CONTINUOUS | CNTL1_BIT::OSR1_8 | CNTL1_BIT::ODR_50HZ, CNTL1_BIT::OSR2_8},
{ Register::CNTL2, CNTL2_BIT::RNG_2G, CNTL2_BIT::SOFT_RST | CNTL2_BIT::SELF_TEST},
};
};
@@ -79,8 +79,6 @@ enum class Register : uint8_t {
CNTL2 = 0x0B, // Control Register 2
CHIP_ID = 0x00,
REG_29 = 0x29,
};
// STATUS
@@ -92,11 +90,11 @@ enum STATUS_BIT : uint8_t {
// CNTL1
enum CNTL1_BIT : uint8_t {
// OSR2[7:6]
OSR2_4 = Bit7, // 10
OSR2_8 = Bit7 | Bit6, // 00
// OSR1[5:4]
OSR1_8 = Bit5 | Bit4, // 11
// ODR[3:2]
ODR_200HZ = Bit3 | Bit2, // 11
ODR_50HZ = Bit2, // 01
// MODE[1:0]
MODE_CONTINUOUS = Bit1 | Bit0, // 11
};
+11 -11
View File
@@ -254,11 +254,11 @@ VOXLPM::print_status()
switch (_pm_type) {
case VOXLPM_TYPE_V2_LTC:
PX4_INFO("- V2 (LTC2964)");
printf("- V2 (LTC2964)\n");
break;
case VOXLPM_TYPE_V3_INA:
PX4_INFO("- V3 (INA231)");
printf("- V3 (INA231)\n");
break;
default:
@@ -267,27 +267,27 @@ VOXLPM::print_status()
switch (_ch_type) {
case VOXLPM_CH_TYPE_VBATT:
PX4_INFO("- type: BATT");
printf("- type: BATT\n");
break;
case VOXLPM_CH_TYPE_P5VDC:
PX4_INFO("- type: P5VDC");
printf("- type: P5VDC\n");
break;
case VOXLPM_CH_TYPE_P12VDC:
PX4_INFO("- type: P12VDC");
printf("- type: P12VDC\n");
break;
default:
PX4_INFO("- type: UNKOWN");
printf("- type: UNKOWN\n");
break;
}
PX4_INFO(" - voltage: %9.4f VDC ", (double)_voltage);
PX4_INFO(" - current: %9.4f ADC ", (double)_amperage);
PX4_INFO(" - shunt: %9.4f mV, %9.4f mA", (double)_vshunt * 1000, (double)_vshuntamps * 1000);
PX4_INFO(" - rsense: %9.6f ohm, cal: %i", (double)_rshunt, _cal);
PX4_INFO(" - meas interval: %u us ", _meas_interval_us);
printf(" - voltage: %9.4f VDC \n", (double)_voltage);
printf(" - current: %9.4f ADC \n", (double)_amperage);
printf(" - shunt: %9.4f mV, %9.4f mA\n", (double)_vshunt * 1000, (double)_vshuntamps * 1000);
printf(" - rsense: %9.6f ohm, cal: %i\n", (double)_rshunt, _cal);
printf(" - meas interval: %u us \n", _meas_interval_us);
}
void
+1 -1
View File
@@ -246,7 +246,7 @@ private:
int measure_ina231();
bool _initialized;
static constexpr unsigned _meas_interval_us{20_ms};
static constexpr unsigned _meas_interval_us{100_ms};
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
-4
View File
@@ -34,10 +34,6 @@ if DRIVERS_UAVCANNODE
bool "Include GNSS fix"
default n
config UAVCANNODE_HARDPOINT_COMMAND
bool "Include hardpoint commands"
default n
config UAVCANNODE_HYGROMETER_MEASUREMENT
bool "Include hygrometer measurement"
default n
@@ -113,10 +113,10 @@ public:
}
// Diagonal matrix
// position variances -- Xx, Yy, Zz (eph/epv are std dev in meters, must square for variance)
fix2.covariance.push_back(gps.eph * gps.eph);
fix2.covariance.push_back(gps.eph * gps.eph);
fix2.covariance.push_back(gps.epv * gps.epv);
// position variances -- Xx, Yy, Zz
fix2.covariance.push_back(gps.eph);
fix2.covariance.push_back(gps.eph);
fix2.covariance.push_back(gps.epv);
// velocity variance -- Vxx, Vyy, Vzz
fix2.covariance.push_back(gps.s_variance_m_s);
fix2.covariance.push_back(gps.s_variance_m_s);
@@ -1,123 +0,0 @@
/****************************************************************************
*
* 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
#include "UavcanSubscriberBase.hpp"
#include <uavcan/equipment/hardpoint/Command.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/actuator_servos.h>
namespace uavcannode
{
class HardpointCommand;
typedef uavcan::MethodBinder<HardpointCommand *,
void (HardpointCommand::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::hardpoint::Command>&)>
HardpointCommandBinder;
class HardpointCommand :
public UavcanSubscriberBase,
private uavcan::Subscriber<uavcan::equipment::hardpoint::Command, HardpointCommandBinder>
{
public:
HardpointCommand(uavcan::INode &node) :
UavcanSubscriberBase(uavcan::equipment::hardpoint::Command::DefaultDataTypeID),
uavcan::Subscriber<uavcan::equipment::hardpoint::Command, HardpointCommandBinder>(node)
{}
bool init()
{
if (start(HardpointCommandBinder(this, &HardpointCommand::callback)) < 0) {
PX4_ERR("uavcan::equipment::hardpoint::Command subscription failed");
return false;
}
return true;
}
void PrintInfo() const override
{
printf("\t%s:%d -> %s\n",
uavcan::equipment::hardpoint::Command::getDataTypeFullName(),
uavcan::equipment::hardpoint::Command::DefaultDataTypeID,
_actuator_servos_pub.get_topic()->o_name);
}
private:
void callback(const uavcan::ReceivedDataStructure<uavcan::equipment::hardpoint::Command> &msg)
{
uint8_t servo_id = msg.hardpoint_id;
actuator_servos_s actuator_servos {};
if (servo_id >= actuator_servos_s::NUM_CONTROLS) {
return;
}
for (uint8_t i = servo_id; i < actuator_servos_s::NUM_CONTROLS; ++i) {
actuator_servos.timestamp = hrt_absolute_time();
actuator_servos.timestamp_sample = actuator_servos.timestamp;
if (msg.command == 1) {
actuator_servos.control[i] = 1; // grip
} else if (msg.command == 0) {
actuator_servos.control[i] = -1; // release
} else {
actuator_servos.control[i] = 0; // do nothing
}
actuator_servos.timestamp = hrt_absolute_time();
actuator_servos.timestamp_sample = actuator_servos.timestamp;
// If ID is not 0 (broadcast), do not iterate
if (servo_id != 0) {
break;
}
}
_actuator_servos_pub.publish(actuator_servos);
}
uORB::Publication<actuator_servos_s> _actuator_servos_pub{ORB_ID(actuator_servos)};
};
} // namespace uavcannode

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