Compare commits

..

1 Commits

Author SHA1 Message Date
Niklas Hauser 4ff589b5a6 [uavcan] Fix unitless actuator range conversion
Input [1000us, 2000us] -> [-1, 1] output.
2025-05-28 11:17:11 +02:00
376 changed files with 5106 additions and 12972 deletions
+1 -7
View File
@@ -54,13 +54,7 @@ jobs:
run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")"
- id: set-branch
run: |
echo "branchname=${{
github.event_name == 'pull_request' &&
format('pr-{0}', github.event.pull_request.number) ||
github.head_ref ||
github.ref_name
}}" >> $GITHUB_OUTPUT
run: echo "::set-output name=branchname::${GITHUB_HEAD_REF:-${GITHUB_REF#refs/heads/}}"
- name: Debug Matrix Output
if: runner.debug == '1'
+16 -17
View File
@@ -7,34 +7,33 @@ See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/ma
| Name | Sector | GitHub | Chat | email
|-------------------------|--------|--------|------|----------------
| Lorenz Meier | Founder | [@LorenzMeier](https://github.com/LorenzMeier) | | <lorenz@px4.io>
| Daniel Agar | Architecture | [@dagar](https://github.com/dagar) | daniel_agar | <daniel@agar.ca>
| Beat Küng | Architecture | [@bkueng](https://github.com/bkueng) | beatkueng | <beat-kueng@gmx.net>
| Ramón Roche | CI / Testing | [@mrpollo](https://github.com/mrpollo) | rroche | <rroche@linuxfoundation.org>
| Mathieu Bresciani | State Estimation | [@bresch](https://github.com/bresch) | mbresch |
| Paul Riseborough | State Estimation | [@priseborough](https://github.com/priseborough) | |
| David Sidrane | RTOS / NuttX | [@davids5](https://github.com/davids5) | david_s5 | <David.Sidrane@Nscdg.com>
| Jayoung Lim | Simulation | [@Jaeyoung-Lim](https://github.com/Jaeyoung-Lim) | jaeyounglim. | <jalim@ethz.ch>
| Beniamino Pozzan | ROS 2 | [@beniaminopozzan](https://github.com/beniaminopozzan) | beniaminopozzan | <beniamino.pozzan@gmail.com>
| Matthias Grob | Multirotor | [@MaEtUgR](https://github.com/MaEtUgR) | maetugr |
| Silvan Fuhrer | Fixed-Wing / VTOL | [@sfuhrer](https://github.com/sfuhrer) | sfuhrer |
| Christian Friedrich | Rover | [@chfriedrich98](https://github.com/chfriedrich98) | christian982564 |
| Pedro Roque | Spacecraft | [@Pedro-Roque](https://github.com/Pedro-Roque) | .pedroroque | <padr@kth.se>
| Jacob Dahl | Simulation | [@dakejahl](https://github.com/dakejahl) | dakejahl | <dahl.jakejacob@gmail.com>
| Lorenz Meier | Founder | [LorenzMeier][LorenzMeier] | | <lorenz@px4.io>
| Daniel Agar | Architecture | [dagar][dagar] | daniel_agar | <daniel@agar.ca>
| Beat Küng | Architecture | [bkueng][bkueng] | beatkueng | <beat-kueng@gmx.net>
| Ramón Roche | CI / Testing | [mrpollo][mrpollo] | rroche | <rroche@linuxfoundation.org>
| Mathieu Bresciani | State Estimation | [bresch][bresch] | mbresch |
| Paul Riseborough | State Estimation | [priseborough][priseborough] | |
| David Sidrane | RTOS / NuttX | [davids5][davids5] | david_s5 | <David.Sidrane@Nscdg.com>
| Jayoung Lim | Simulation | [Jaeyoung-Lim][Jaeyoung-Lim] | jaeyounglim. | <jalim@ethz.ch>
| Beniamino Pozzan | ROS 2 | [beniaminopozzan][beniaminopozzan] | beniaminopozzan | <beniamino.pozzan@gmail.com>
| Matthias Grob | Multirotor | [MaEtUgR][MaEtUgR] | maetugr |
| Silvan Fuhrer | Fixed-Wing / VTOL | [sfuhrer][sfuhrer] | sfuhrer |
| Christian Friedrich | Rover | [chfriedrich98][chfriedrich98] | christian982564 |
| Pedro Roque | Spacecraft | [Pedro-Roque][Pedro-Roque] | .pedroroque | <padr@kth.se>
**Documentation Maintainers**
| Name | GitHub | Chat | email
|------|--------|------|----------------------
| Hamish Willee | [@hamishwillee](https://github.com/hamishwillee) | hamishwillee |
| Hamish Willee | [hamishwillee][hamishwillee] | hamishwillee |
**Release Managers**
| Name | GitHub | Chat | email
|------|--------|------|----------------------
| Ramón Roche | [@mrpollo](https://github.com/mrpollo) | rroche | <rroche@linuxfoundation.org>
| Daniel Agar | [@dagar](https://github.com/dagar) | daniel_agar | <daniel@agar.ca>
| Ramón Roche | [mrpollo][mrpollo] | rroche | <rroche@linuxfoundation.org>
| Daniel Agar | [dagar][dagar] | daniel_agar | <daniel@agar.ca>
**Retired Maintainers**
+11 -22
View File
@@ -110,36 +110,25 @@ if [ -n "${PX4_SIM_MODEL#*gz_}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then
MODEL_NAME="${PX4_SIM_MODEL#*gz_}"
MODEL_NAME_INSTANCE="${MODEL_NAME}_${px4_instance}"
sdf_pose_str=""
POSE_ARG=""
if [ -n "${PX4_GZ_MODEL_POSE}" ]; then
pose_x=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $1}')
pose_y=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $2}')
pose_z=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $3}')
pose_roll=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $4}')
pose_pitch=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $5}')
pose_yaw=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $6}')
pos_x=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $1}')
pos_y=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $2}')
pos_z=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $3}')
pos_x=${pos_x:-0}
pos_y=${pos_y:-0}
pos_z=${pos_z:-0}
pose_x=${pose_x:-0}
pose_y=${pose_y:-0}
pose_z=${pose_z:-0}
pose_roll=${pose_roll:-0}
pose_pitch=${pose_pitch:-0}
pose_yaw=${pose_yaw:-0}
sdf_pose_str="<pose> ${pose_x} ${pose_y} ${pose_z} ${pose_roll} ${pose_pitch} ${pose_yaw} </pose>"
echo "INFO [init] Gazebo model pose: ${pose_x} ${pose_y} ${pose_z} ${pose_roll} ${pose_pitch} ${pose_yaw}"
POSE_ARG=", pose: { position: { x: ${pos_x}, y: ${pos_y}, z: ${pos_z} } }"
echo "INFO [init] Spawning model at position: ${pos_x} ${pos_y} ${pos_z}"
fi
echo "INFO [init] Spawning Gazebo model"
# include the actual SDF in this one, containing the pose if given
sdf_str="<sdf version=\"1.6\"> <include> <uri>file://${PX4_GZ_MODELS}/${MODEL_NAME}/model.sdf</uri> ${sdf_pose_str} </include> </sdf>"
echo "INFO [init] Spawning model"
# Spawn model
${gz_command} service -s "/world/${PX4_GZ_WORLD}/create" --reqtype gz.msgs.EntityFactory \
--reptype gz.msgs.Boolean --timeout 5000 \
--req "name: \"${MODEL_NAME_INSTANCE}\", allow_renaming: false, sdf: '${sdf_str}'" > /dev/null 2>&1
--req "sdf_filename: \"${PX4_GZ_MODELS}/${MODEL_NAME}/model.sdf\", name: \"${MODEL_NAME_INSTANCE}\", allow_renaming: false${POSE_ARG}" > /dev/null 2>&1
# Wait for model to spawn
sleep 1
+4 -9
View File
@@ -295,15 +295,10 @@ then
# for multi intances setup, add namespace prefix
uxrce_dds_ns="-n px4_$px4_instance"
fi
if [ "${PX4_UXRCE_DDS_NS+x}" ]; then
# Override, as variable is set (empty or not)
if [ -n "$PX4_UXRCE_DDS_NS" ]; then
# Override namespace if environment variable is non-empty
uxrce_dds_ns="-n $PX4_UXRCE_DDS_NS"
else
# Clear namespace if variable is empty
uxrce_dds_ns=""
fi
if [ -n "$PX4_UXRCE_DDS_NS" ]
then
# Override namespace if environment variable is defined
uxrce_dds_ns="-n $PX4_UXRCE_DDS_NS"
fi
if [ -n "$ROS_DOMAIN_ID" ]
then
+1 -1
View File
@@ -39,7 +39,7 @@ set VEHICLE_TYPE none
# Airframe parameter versioning
# Value set to 1 by default but can optionally be overridden in the airframe configuration startup script.
# Airframe maintainers can ensure a reset to the airframe defaults during an update by increasing by one.
# e.g. add line "set PARAM_DEFAULTS_VER 2" in your airframe file to build the first update that enforces a reset.
# e.g. add line "set PARAM_DEFAULTS_VER 2" in your airframe file to build the first update that enfoces a reset.
set PARAM_DEFAULTS_VER 1
#
+22 -2
View File
@@ -2,7 +2,19 @@
if [ -z ${PX4_DOCKER_REPO+x} ]; then
echo "guessing PX4_DOCKER_REPO based on input";
if [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then
if [[ $@ =~ .*px4_fmu.* ]]; then
# nuttx-px4fmu-v{1,2,3,4,5}
PX4_DOCKER_REPO="px4io/px4-dev-nuttx-focal:2022-08-12"
elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*beaglebone.* ]] || [[ $@ =~ .*pilotpi.default ]] || [[ $@ =~ .*navigator.* ]]; then
# beaglebone_blue_default, emlid_navio2_default, px4_raspberrypi_default, scumaker_pilotpi_default, bluerobotics_navigator_default
PX4_DOCKER_REPO="px4io/px4-dev-armhf:2023-06-26"
elif [[ $@ =~ .*pilotpi.arm64 ]]; then
# scumaker_pilotpi_arm64
PX4_DOCKER_REPO="px4io/px4-dev-aarch64:2022-08-12"
elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*bebop.* ]]; then
# posix_rpi_cross, posix_bebop_default
PX4_DOCKER_REPO="px4io/px4-dev-armhf:2023-06-26"
elif [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then
# clang tools
PX4_DOCKER_REPO="px4io/px4-dev-clang:2021-02-04"
elif [[ $@ =~ .*tests* ]]; then
@@ -15,9 +27,17 @@ fi
# otherwise default to nuttx
if [ -z ${PX4_DOCKER_REPO+x} ]; then
PX4_DOCKER_REPO="px4io/px4-dev:v1.16.0-ondemand"
PX4_DOCKER_REPO="px4io/px4-dev-nuttx-focal:2022-08-12"
fi
# docker hygiene
#Delete all stopped containers (including data-only containers)
# docker container prune
#Delete all 'untagged/dangling' (<none>) images
# docker image prune
echo "PX4_DOCKER_REPO: $PX4_DOCKER_REPO";
PWD=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )
-97
View File
@@ -2,7 +2,6 @@
"""
Generate docs from .msg files
Also generates docs/en/middleware/dds_topics.md from dds_topics.yaml
"""
import os
@@ -10,99 +9,6 @@ import argparse
import sys
import yaml
def generate_dds_yaml_doc(allMessageFiles, output_file = 'dds_topics.md'):
"""
Generates human readable version of dds_topics.yaml.
Default output is to docs/en/middleware/dds_topics.md
"""
dds_file_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../../src/modules/uxrce_dds_client/dds_topics.yaml")
output_file_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),f"../../docs/en/middleware/{output_file}")
try:
with open(dds_file_path, 'r') as file:
data = yaml.safe_load(file)
# Get messages and topics that are not published by default
# Start by getting all that are published.
all_messages_in_source = set()
all_message_types =set()
all_topics =set()
for message in data["publications"]:
all_message_types.add(message['type'].split("::")[-1])
all_topics.add(message['topic'].split('/')[-1])
for message in data["subscriptions"]:
all_message_types.add(message['type'].split("::")[-1])
all_topics.add(message['topic'].split('/')[-1])
if data["subscriptions_multi"]: # There is none now
dds_markdown += "None\n"
for message in data["subscriptions_multi"]:
all_message_types.add(message['type'].split("::")[-1])
all_topics.add(message['topic'].split('/')[-1])
for message in allMessageFiles:
all_messages_in_source.add(message.split('/')[-1].split('.')[0])
messagesNotExported = all_messages_in_source - all_message_types
# write out the dds file
dds_markdown="""# dds_topics.yaml — PX4 Topics Exposed to ROS 2
::: info
This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
## Publications
Topic | Type| Rate Limit
--- | --- | ---
"""
for message in data["publications"]:
type = message['type']
px4Type=type.split("::")[-1]
dds_markdown += f"`{message['topic']}` | [{type}](../msg_docs/{px4Type}.md) | {message.get('rate_limit','')}\n"
dds_markdown += "\n## Subscriptions\n\nTopic | Type\n--- | ---\n"
for message in data["subscriptions"]:
type = message['type']
px4Type=type.split("::")[-1]
dds_markdown += f"{message['topic']} | [{type}](../msg_docs/{px4Type}.md)\n"
dds_markdown += "\n## Subscriptions Multi\n\n"
if not data["subscriptions_multi"]: # There is none now
dds_markdown += "None\n"
else:
print("Warning - we now have subscription_multi data - check format")
dds_markdown += "Topic | Type\n--- | ---\n"
for message in data["subscriptions_multi"]:
dds_markdown += f"{message['topic']} | {message['type']}\n"
if messagesNotExported:
# Print the topics that are not exported to DDS
dds_markdown += "\n## Not Exported\n\nThese messages are not listed in the yaml file.\nThey are not build into the module, and hence are neither published or subscribed."
dds_markdown += "\n\n::: details See messages\n"
for item in messagesNotExported:
dds_markdown += f"\n- [{item}](../msg_docs/{item}.md)"
dds_markdown += "\n:::\n" # End of details block
#print(dds_markdown)
with open(output_file_path, 'w') as content_file:
content_file.write(dds_markdown)
except yaml.YAMLError as exc:
print(f"Error parsing YAML: {exc}")
except FileNotFoundError:
print(f"Error: {dds_file_path} not found.")
def get_msgs_list(msgdir):
"""
Makes a list of relative paths of .msg files in the given directory
@@ -124,7 +30,6 @@ def get_msgs_list(msgdir):
if __name__ == "__main__":
parser = argparse.ArgumentParser(description='Generate docs from .msg files')
parser.add_argument('-d', dest='dir', help='output directory', required=True)
args = parser.parse_args()
@@ -227,5 +132,3 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
index_file = os.path.join(output_dir, 'index.md')
with open(index_file, 'w') as content_file:
content_file.write(index_text)
generate_dds_yaml_doc(msg_files)
@@ -10,7 +10,6 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
@@ -132,7 +132,6 @@ ENTRY(_stext)
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
EXTERN(board_get_manifest)
SECTIONS
{
@@ -48,7 +48,6 @@ else()
i2c.cpp
init.c
led.c
mtd.cpp
spi.cpp
timer_config.cpp
usb.c
@@ -1,76 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2025 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 <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// KiB BS nB
static const px4_mft_device_t spi2 = { // FM25V01A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32)
.bus_type = px4_mft_device_t::SPI,
.devid = SPIDEV_FLASH(0)
};
static const px4_mtd_entry_t fmum_fram = {
.device = &spi2,
.npart = 1,
.partd = {
{
.type = MTD_PARAMETERS,
.path = "/fs/mtd_params",
.nblocks = (32768 / (1 << CONFIG_RAMTRON_EMULATE_PAGE_SHIFT))
},
},
};
static const px4_mtd_manifest_t board_mtd_config = {
.nconfigs = 1,
.entries = {
&fmum_fram
}
};
static const px4_mft_entry_s mtd_mft = {
.type = MTD,
.pmft = (void *) &board_mtd_config,
};
static const px4_mft_s mft = {
.nmft = 1,
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
{
return &mft;
}
@@ -34,25 +34,75 @@
#pragma once
// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 // 1 DMA1:37 IIM-42653
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 // 2 DMA1:38 IIM-42653
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 // 3 DMA1:41 GPS1
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 // 4 DMA1:42 GPS1
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 // 5 DMA1:71 RC
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 // 6 DMA1:72 RC
// Timer 4 (DMAMAP_DMA12_TIM4UP_0) // 7 DMA1:32 TIM4UP/TIM4CH1-4
// Timer 5 (DMAMAP_DMA12_TIM5UP_0) // 8 DMA1:50 TIM5UP/TIM5CH1-4
// V
// Timer 4 Channel 1 /* DMA1:29 TIM4CH1 */
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 IIM-42653 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 IIM-42653 */
//#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */
//#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */
//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */
//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */
// Timer 8 Channel 1 /* DMA1:47 TIM8CH1 */
// Timer 8 Channel 2 /* DMA1:48 TIM8CH2 */
// Timer 8 Channel 3 /* DMA1:49 TIM8CH3 */
// Timer 8 Channel 4 /* DMA1:50 TIM8CH4 */
// Timer 5 Channel 1 /* DMA1:55 TIM5CH1 */
// Timer 5 Channel 2 /* DMA1:56 TIM5CH2 */
// Timer 5 Channel 3 /* DMA1:57 TIM5CH3 */
// Timer 5 Channel 4 /* DMA1:58 TIM5CH4 */
// #define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 UART4 */
// #define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 UART4 */
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 RC */
// #define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 RC */
// Assigned in timer_config.cpp
// Timer 4 /* 7 DMA1:32 TIM4UP */
// Timer 5 /* 8 DMA1:50 TIM5UP */
// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 // 1 DMA2:43 VTX
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 // 2 DMA2:65 VTX
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 // 3 DMA2:66 VTX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 // 4 DMA2:79 TELEM1
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 // 5 DMA2:80 TELEM1
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 // 6 DMA2:45 DEBUG
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 // 7 DMA2:46 DEBUG
// available
// V
// Timer 4 Channel 1 /* DMA2:29 TIM4CH1 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* 3 DMA2:43 TELEM3 */
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* 4 DMA2:44 TELEM3 */
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */
// Timer 8 Channel 1 /* DMA2:47 TIM8CH1 */
// Timer 8 Channel 2 /* DMA2:48 TIM8CH2 */
// Timer 8 Channel 3 /* DMA2:49 TIM8CH3 */
// Timer 8 Channel 4 /* DMA2:50 TIM8CH4 */
// Timer 5 Channel 1 /* DMA2:55 TIM5CH1 */
// Timer 5 Channel 2 /* DMA2:56 TIM5CH2 */
// Timer 5 Channel 3 /* DMA2:57 TIM5CH3 */
// Timer 5 Channel 4 /* DMA2:58 TIM5CH4 */
//#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */
//#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */
// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX // 1 BDMA:11 SPI J11
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX // 2 BDMA:12 SPI J11
// V
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */
+2 -1
View File
@@ -260,6 +260,8 @@ CONFIG_USART1_TXDMA=y
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_RXDMA=y
@@ -270,7 +272,6 @@ CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
@@ -1,5 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m4"
CONFIG_BOARD_ROMFSROOT=""
CONFIG_BOARD_CONSTRAINED_MEMORY=y
CONFIG_DRIVERS_BOOTLOADERS=y
-56
View File
@@ -1,56 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m4"
CONFIG_BOARD_ROMFSROOT="cannode"
CONFIG_BOARD_CONSTRAINED_FLASH=y
CONFIG_BOARD_CONSTRAINED_MEMORY=y
CONFIG_BOARD_EXTERNAL_METADATA=y
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_COMMON_BAROMETERS=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_BOOTLOADERS=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_COMMON_HYGROMETERS=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_DRIVERS_UAVCANNODE=y
CONFIG_UAVCANNODE_ARMING_STATUS=y
CONFIG_UAVCANNODE_BEEP_COMMAND=y
CONFIG_UAVCANNODE_ESC_RAW_COMMAND=y
CONFIG_UAVCANNODE_ESC_STATUS=y
CONFIG_UAVCANNODE_FLOW_MEASUREMENT=y
CONFIG_UAVCANNODE_GNSS_FIX=y
CONFIG_UAVCANNODE_HYGROMETER_MEASUREMENT=y
CONFIG_UAVCANNODE_LIGHTS_COMMAND=y
CONFIG_UAVCANNODE_MAGNETIC_FIELD_STRENGTH=y
CONFIG_UAVCANNODE_RANGE_SENSOR_MEASUREMENT=y
CONFIG_UAVCANNODE_RAW_AIR_DATA=y
CONFIG_UAVCANNODE_RAW_IMU=y
CONFIG_UAVCANNODE_RTK_DATA=y
CONFIG_UAVCANNODE_SERVO_ARRAY_COMMAND=y
CONFIG_UAVCANNODE_STATIC_PRESSURE=y
CONFIG_UAVCANNODE_STATIC_TEMPERATURE=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
@@ -1,13 +0,0 @@
{
"board_id": 83,
"magic": "PX4FWv1",
"description": "Firmware for the ARK CANnode board",
"image": "",
"build_time": 0,
"summary": "ARKCANNODE",
"version": "0.1",
"image_size": 0,
"image_maxsize": 2080768,
"git_identity": "",
"board_revision": 0
}
@@ -1,12 +0,0 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default MBE_ENABLE 0
param set-default SENS_IMU_CLPNOTI 0
param set-default SENS_EN_AUAVX 1
pwm_out start
dshot start
@@ -1,123 +0,0 @@
#!/bin/sh
#
# board sensors init
#------------------------------------------------------------------------------
icm42688p -R 0 -s start
if param compare -s SENS_EN_BATT 1
then
batt_smbus start -X
fi
# Lidar-Lite on I2C
if param compare -s SENS_EN_LL40LS 2
then
ll40ls start -X
fi
# mappydot lidar sensor
if param compare -s SENS_EN_MPDT 1
then
mappydot start -X
fi
# mb12xx sonar sensor
if param greater -s SENS_EN_MB12XX 0
then
mb12xx start -X
fi
# Lightware i2c lidar sensor
if param greater -s SENS_EN_SF1XX 0
then
lightware_laser_i2c start -X
fi
# vl53l1x i2c distance sensor
if param compare -s SENS_EN_VL53L1X 1
then
vl53l1x start -X
fi
# ADIS16448 spi external IMU
if param compare -s SENS_EN_ADIS164X 1
then
if param compare -s SENS_OR_ADIS164X 0
then
adis16448 -S start
fi
if param compare -s SENS_OR_ADIS164X 4
then
adis16448 -S start -R 4
fi
fi
# Eagle Tree airspeed sensor external I2C
if param compare -s SENS_EN_ETSASPD 1
then
ets_airspeed start -X
fi
# Sensirion SDP3X differential pressure sensor external I2C
if param compare -s SENS_EN_SDP3X 1
then
if ! sdp3x start -X
then
# try another common address
sdp3x start -X -a 0x22
fi
fi
# SHT3x temperature and hygrometer sensor, external I2C
if param compare -s SENS_EN_SHT3X 1
then
sht3x start -X
sht3x start -X -a 0x45
fi
# TE MS4525DO differential pressure sensor external I2C
if param compare -s SENS_EN_MS4525DO 1
then
ms4525do start -X
fi
# TE MS5525DSO differential pressure sensor external I2C
if param compare -s SENS_EN_MS5525DS 1
then
ms5525dso start -X
fi
# IR-LOCK sensor external I2C
if param compare -s SENS_EN_IRLOCK 1
then
irlock start -X
fi
# SPL06 sensor external I2C
if param compare -s SENS_EN_SPL06 1
then
spl06 -X start
spl06 -X -a 0x77 start
fi
# AUAV absolute/differential pressure sensor external I2C
if param greater -s SENS_EN_AUAVX 0
then
auav start -D -X
auav start -A -X
fi
# probe for optional external I2C devices
icm20948_i2c_passthrough -X -q start
# compasses
hmc5883 -T -X -q start
ist8308 -X -q start
ist8310 -X -q start
iis2mdc -X -q start
lis3mdl -X -q start
qmc5883l -X -q start
rm3100 -X -q start
# start last (wait for possible icm20948 passthrough mode)
ak09916 -X -q start
@@ -1,56 +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_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/auterion/cannode/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32=y
CONFIG_ARCH_CHIP_STM32F412CE=y
CONFIG_ARCH_INTERRUPTSTACK=4096
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BINFMT_DISABLE=y
CONFIG_BOARDCTL=y
CONFIG_BOARD_LOOPSPERMSEC=16717
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DISABLE_MOUNTPOINT=y
CONFIG_EXPERIMENTAL=y
CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=4096
CONFIG_INIT_STACKSIZE=4096
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MM_REGIONS=2
CONFIG_NAME_MAX=0
CONFIG_NUNGET_CHARS=0
CONFIG_PREALLOC_TIMERS=0
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=262144
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_DISABLE_BUFFERING=y
CONFIG_STM32_FLASH_CONFIG_G=y
CONFIG_STM32_NOEXT_VECTORS=y
CONFIG_TASK_NAME_SIZE=0
CONFIG_USEC_PER_TICK=1000
@@ -1,149 +0,0 @@
/************************************************************************************
* configs/px4fmu/include/board.h
* include/arch/board/board.h
*
* Copyright (C) 2009 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.
*
************************************************************************************/
#include "board_dma_map.h"
#ifndef __ARCH_BOARD_BOARD_H
#define __ARCH_BOARD_BOARD_H
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
#include <stm32.h>
/* HSI - 8 MHz RC factory-trimmed
* LSI - 32 KHz RC
* HSE - 8 MHz Crystal
* LSE - not installed
*/
#define STM32_BOARD_USEHSE 1
#define STM32_BOARD_XTAL 8000000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
/* Main PLL Configuration */
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(384)
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_4
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(8)
#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2)
#define STM32_RCC_PLLI2SCFGR_PLLI2SM RCC_PLLI2SCFGR_PLLI2SM(16)
#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
#define STM32_RCC_PLLI2SCFGR_PLLI2SSRC RCC_PLLI2SCFGR_PLLI2SSRC(0) /* HSE or HSI depending on PLLSRC of PLLCFGR*/
#define STM32_RCC_DCKCFGR2_CK48MSEL RCC_DCKCFGR2_CK48MSEL_PLL
#define STM32_RCC_DCKCFGR2_FMPI2C1SEL RCC_DCKCFGR2_FMPI2C1SEL_APB
#define STM32_RCC_DCKCFGR2_SDIOSEL RCC_DCKCFGR2_SDIOSEL_48MHZ
#define STM32_SYSCLK_FREQUENCY 96000000ul
/* AHB clock (HCLK) is SYSCLK (96MHz) */
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* Same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/2 (48MHz) */
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timers driven from APB1 will be twice PCLK1 (see page 112 of reference manual) */
#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)
/* APB2 clock (PCLK2) is HCLK (96MHz) */
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY)
/* Timers driven from APB2 will be PCLK2 since no prescale division */
#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM9_CLKIN (STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM10_CLKIN (STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM11_CLKIN (STM32_PCLK2_FREQUENCY)
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx otherwise frequency is 2xAPBx. */
#define BOARD_TIM2_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
#define BOARD_TIM3_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
#define BOARD_TIM4_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
#define BOARD_TIM5_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
#define BOARD_TIM6_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
#define BOARD_TIM7_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
#define BOARD_TIM8_FREQUENCY (2 * STM32_PCLK2_FREQUENCY)
/* Alternate function pin selections ************************************************/
/* UARTs */
#define GPIO_USART1_RX GPIO_USART1_RX_2
#define GPIO_USART1_TX GPIO_USART1_TX_3
#define GPIO_USART2_RX GPIO_USART2_RX_1
#define GPIO_USART2_TX GPIO_USART2_TX_1
/* CAN */
#define GPIO_CAN1_RX GPIO_CAN1_RX_1
#define GPIO_CAN1_TX GPIO_CAN1_TX_1
/* SPI */
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 /* PB13 */
/* I2C */
#define GPIO_MCU_I2C1_SCL
#define GPIO_MCU_I2C1_SDA
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
#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)
#endif /* __ARCH_BOARD_BOARD_H */
@@ -1,50 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
// DMA1 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX // DMA1, Stream 3, Channel 0
#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX // DMA1, Stream 4, Channel 0
// DMA2 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_2 // DMA2, Stream 2, Channel 3
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2 // DMA2, Stream 5, Channel 3
// Assigned in timer_config.cpp
// Timer 2 /* DMA1, Stream 7, Channel 3 DMAMAP_TIM2_UP_2 */
// Timer 3 /* DMA1, Stream 2, Channel 5 DMAMAP_TIM3_UP */
// Timer 4 /* DMA1, Stream 6, Channel 2 DMAMAP_TIM4_UP */
@@ -1,153 +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_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_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_MOUNT is not set
# CONFIG_NSH_DISABLE_MV 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_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/auterion/cannode/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32=y
CONFIG_ARCH_CHIP_STM32F412CE=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_LOOPSPERMSEC=16717
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEFAULT_SMALL=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_CROMFS=y
CONFIG_FS_ROMFS=y
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=2624
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_MAX_EXITFUNS=1
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MM_REGIONS=2
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_VARS=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=262144
CONFIG_RAM_START=0x20000000
CONFIG_RAW_BINARY=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=254
CONFIG_SCHED_HPWORKSTACKSIZE=3000
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
CONFIG_SCHED_WAITPID=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=32
CONFIG_STM32_ADC1=y
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
CONFIG_STM32_DMA1=y
CONFIG_STM32_DMA2=y
CONFIG_STM32_FLASH_CONFIG_G=y
CONFIG_STM32_FLASH_PREFETCH=y
CONFIG_STM32_FLOWCONTROL_BROKEN=y
CONFIG_STM32_I2C1=y
CONFIG_STM32_JTAG_SW_ENABLE=y
CONFIG_STM32_PWR=y
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI1_DMA=y
CONFIG_STM32_SPI1_DMA_BUFFER=2048
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI2_DMA=y
CONFIG_STM32_SPI2_DMA_BUFFER=2048
CONFIG_STM32_USART1=y
CONFIG_STM32_USART2=y
CONFIG_STM32_USART_BREAKS=y
CONFIG_STM32_WWDG=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1100
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_SERIAL_CONSOLE=y
CONFIG_USART2_TXBUFSIZE=1100
CONFIG_USEC_PER_TICK=1000
@@ -1,134 +0,0 @@
/****************************************************************************
* nuttx-config/scripts/canbootloader_script.ld
*
* Copyright (C) 2015 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 STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
* 256Kb of SRAM. SRAM is split up into three blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
* 3) 64Kb of SRAM beginning at address 0x2002:0000
* 4) 64Kb of TCM SRAM beginning at address 0x1000: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.
*
* The first 0x10000 of flash is reserved for the bootloader.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* 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)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.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,146 +0,0 @@
/****************************************************************************
* scripts/ld.script
*
* Copyright (C) 2011 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 STM32F412CG has 1Mb of FLASH beginning at address 0x0800:0000 and
* 256Kb of SRAM. SRAM is split up into three blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
* 3) 64Kb of SRAM beginning at address 0x2002:0000
* 4) 64Kb of TCM SRAM beginning at address 0x1000: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.
*
* The first 0x10000 of flash is reserved for the bootloader.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08010000, LENGTH = 928K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* 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(8);
/*
* This section positions the app_descriptor_t used
* by the make_can_boot_descriptor.py tool to set
* the application image's descriptor so that the
* uavcan bootloader has the ability to validate the
* image crc, size etc
*/
KEEP(*(.app_descriptor))
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.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,68 +0,0 @@
############################################################################
#
# Copyright (c) 2020 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 "canbootloader")
add_library(drivers_board
boot_config.h
boot.c
led.c
led.h
)
target_link_libraries(drivers_board
PRIVATE
nuttx_arch
nuttx_drivers
canbootloader
)
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader)
else()
add_library(drivers_board
can.c
i2c.cpp
init.c
led.c
spi.cpp
timer_config.cpp
)
target_link_libraries(drivers_board
PRIVATE
arch_spi
drivers__led # drv_led_start
nuttx_arch
nuttx_drivers
px4_layer
)
endif()
-115
View File
@@ -1,115 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
*
* board internal definitions
*/
#pragma once
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
/* CAN Silent mode control */
#define GPIO_CAN1_SILENT_S0 /* PC14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN14)
/* CAN termination software control */
#define GPIO_CAN1_TERMINATION /* PC15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15)
#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
/* Boot config */
#define GPIO_BOOT_CONFIG /* PH1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTH|GPIO_PIN1|GPIO_EXTI)
/* ICM42688p FSYNC */
#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
/* LEDs are driven with open drain to support Anode to 5V or 3.3V */
#define GPIO_TIM1_CH1 /* PA8 */ (GPIO_TIM1_CH1_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
#define GPIO_TIM1_CH2 /* PA9 */ (GPIO_TIM1_CH2_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
#define GPIO_TIM1_CH3 /* PA10 */ (GPIO_TIM1_CH3_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
/* PWM Outputs */
#define BOARD_NUM_IO_TIMERS 3
#define DIRECT_PWM_OUTPUT_CHANNELS 8
#define GPIO_TIM2_CH1_RESET /* PA0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
#define GPIO_TIM2_CH2_RESET /* PA1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
#define GPIO_TIM2_CH3_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
#define GPIO_TIM3_CH1_RESET /* PB4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4)
#define GPIO_TIM3_CH2_RESET /* PB5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
#define GPIO_TIM3_CH3_RESET /* PB0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
#define GPIO_TIM3_CH4_RESET /* PB1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
#define GPIO_TIM4_CH4_RESET /* PB7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN7)
#define GPIO_I2C1_SCL_RESET /* PB6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6)
#define GPIO_I2C1_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
#define GPIO_USART1_RX_GPIO /* PB3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
#define GPIO_USART1_TX_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
#define GPIO_USART2_RX_GPIO /* PA3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
#define GPIO_USART2_TX_GPIO /* PA2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
#define FLASH_BASED_PARAMS
/* High-resolution timer */
#define HRT_TIMER 8 /* use timer 8 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
#define PX4_GPIO_INIT_LIST { \
GPIO_CAN1_SILENT_S0, \
GPIO_CAN1_TERMINATION, \
GPIO_42688P_FSYNC, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_I2C1_SCL_RESET, \
GPIO_I2C1_SDA_RESET, \
}
__BEGIN_DECLS
#define BOARD_HAS_N_S_RGB_LED 1
#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED
#ifndef __ASSEMBLY__
extern void stm32_spiinitialize(void);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS
-188
View File
@@ -1,188 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include "boot_config.h"
#include "board.h"
#include <debug.h>
#include <string.h>
#include <arch/board/board.h>
#include <nuttx/board.h>
#include "led.h"
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
stm32_configgpio(GPIO_CAN1_SILENT_S0);
stm32_configgpio(GPIO_CAN1_TERMINATION);
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
#endif
}
/************************************************************************************
* Name: board_deinitialize
*
* Description:
* This function is called by the bootloader code prior to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void board_deinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
}
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrieve the product name. The returned value is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The maximum number of charter that can be written
*
* Returned Value:
* The length of characters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
{
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
}
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
{
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
hw_version->major = HW_VERSION_MAJOR;
hw_version->minor = HW_VERSION_MINOR;
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
}
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
typedef begin_packed_struct struct led_t {
uint8_t red;
uint8_t green;
uint8_t blue;
uint8_t hz;
} end_packed_struct led_t;
static const led_t i2l[] = {
led(0, off, 0, 0, 0, 0),
led(1, reset, 128, 128, 128, 30),
led(2, autobaud_start, 0, 128, 0, 1),
led(3, autobaud_end, 0, 128, 0, 2),
led(4, allocation_start, 0, 0, 64, 2),
led(5, allocation_end, 0, 128, 64, 3),
led(6, fw_update_start, 32, 128, 64, 3),
led(7, fw_update_erase_fail, 32, 128, 32, 3),
led(8, fw_update_invalid_response, 64, 0, 0, 1),
led(9, fw_update_timeout, 64, 0, 0, 2),
led(a, fw_update_invalid_crc, 64, 0, 0, 4),
led(b, jump_to_app, 0, 128, 0, 10),
};
void board_indicate(uiindication_t indication)
{
rgb_led(i2l[indication].red,
i2l[indication].green,
i2l[indication].blue,
i2l[indication].hz);
}
-134
View File
@@ -1,134 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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 boot_config.h
*
* bootloader definitions that configures the behavior and options
* of the Boot loader
* This file is relies on the parent folder's boot_config.h file and defines
* different usages of the hardware for bootloading
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/* Bring in the board_config.h definitions
* todo:make this be pulled in from a targed's build
* files in nuttx*/
#include "board_config.h"
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_flash.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
//todo:wrap OPT_x in in ifdefs for command line definitions
#define OPT_TBOOT_MS 3000
#define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 50
#define OPT_BL_NUMBER_TIMERS 7
/*
* This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware.
* This Option is the default policy and can be overridden by
* a jumper
* When this Policy is set, the node will ignore tboot and
* wait indefinitely for a GetNodeInfo request before booting.
*
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
* the polarity of the jumper to be True Active
*
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
* Jumper
* yes 1 0 x
* yes 1 1 Active
* no 1 1 Not Active
* no 0 0 X
* yes 0 1 Active
* no 0 1 Not Active
*
*/
#define OPT_WAIT_FOR_GETNODEINFO 0
/* The ARK CANnode uses PH1 for GPIO_BOOT_CONFIG but it is not
* compatible with px4_arch_gpioread as Port H = 7 which is greater
* than STM32_NPORTS
* #define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 0
*/
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1
#define OPT_ENABLE_WD 1
#define OPT_RESTART_TIMEOUT_MS 20000
/* Reserved for the Booloader */
#define OPT_BOOTLOADER_SIZE_IN_K (1024*64)
/* Reserved for the application out of the total
* system flash minus the BOOTLOADER_SIZE_IN_K
*/
#define OPT_APPLICATION_RESERVER_IN_K 0
#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
#define FLASH_BASE STM32_FLASH_BASE
#define FLASH_SIZE STM32_FLASH_SIZE
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
/* If this board uses big flash that have large sectors */
#define OPT_USE_YIELD
/* Bootloader Option*****************************************************************
*
*/
#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI)
-130
View File
@@ -1,130 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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 can.c
*
* Board-specific CAN functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/can/can.h>
#include <arch/board/board.h>
#include "chip.h"
#include "arm_internal.h"
#include "stm32.h"
#include "stm32_can.h"
#include "board_config.h"
#ifdef CONFIG_CAN
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
# undef CONFIG_STM32_CAN2
#endif
#ifdef CONFIG_STM32_CAN1
# define CAN_PORT 1
#else
# define CAN_PORT 2
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
int can_devinit(void);
/************************************************************************************
* Name: can_devinit
*
* Description:
* All STM32 architectures must provide the following interface to work with
* examples/can.
*
************************************************************************************/
int can_devinit(void)
{
static bool initialized = false;
struct can_dev_s *can;
int ret;
/* Check if we have already initialized */
if (!initialized) {
/* Call stm32_caninitialize() to get an instance of the CAN interface */
can = stm32_caninitialize(CAN_PORT);
if (can == NULL) {
canerr("ERROR: Failed to get CAN interface\n");
return -ENODEV;
}
/* Register the CAN driver at "/dev/can0" */
ret = can_register("/dev/can0", can);
if (ret < 0) {
canerr("ERROR: can_register failed: %d\n", ret);
return ret;
}
/* Now we are initialized */
initialized = true;
}
return OK;
}
#endif
-38
View File
@@ -1,38 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusExternal(1),
};
-186
View File
@@ -1,186 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
*
* board specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialization.
*/
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/board.h>
#include <stm32.h>
#include "board_config.h"
#include "led.h"
#include <stm32_uart.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <drivers/drv_watchdog.h>
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_arch/io_timer.h>
# if defined(FLASH_BASED_PARAMS)
# include <parameters/flashparams/flashfs.h>
#endif
/************************************************************************************
* 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)
{
// Configure the GPIO pins to outputs and keep them low.
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
px4_arch_configgpio(io_timer_channel_get_gpio_output(i));
}
/*
* On resets invoked from system (not boot) insure we establish a low
* output state (discharge the pins) on PWM pins before they become inputs.
*/
if (status >= 0) {
up_mdelay(400);
}
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
// Reset all PWM to Low outputs.
board_on_reset(-1);
watchdog_init();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
// Configure SPI all interfaces GPIO & enable power.
stm32_spiinitialize();
}
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
px4_platform_init();
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
#if defined(FLASH_BASED_PARAMS)
static sector_descriptor_t params_sector_map[] = {
{2, 16 * 1024, 0x08008000},
{3, 16 * 1024, 0x0800C000},
{0, 0, 0},
};
/* Initialize the flashfs layer to use heap allocated memory */
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);
}
#endif // FLASH_BASED_PARAMS
/* Configure the HW based on the manifest */
//px4_platform_configure();
return OK;
}
-124
View File
@@ -1,124 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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 led.c
*
* LED backend.
*/
#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>
#include "led.h"
#define TMR_BASE STM32_TIM1_BASE
#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN
#define TMR_REG(o) (TMR_BASE+(o))
void rgb_led(int r, int g, int b, int freqs)
{
long fosc = TMR_FREQUENCY;
long prescale = 2048;
long p1s = fosc / prescale;
long p0p5s = p1s / 2;
uint16_t val;
static bool once = 0;
if (!once) {
once = 1;
/* Enable Clock to Block */
modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
/* Reload */
val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
val |= ATIM_EGR_UG;
putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
/* Set Prescaler STM32_TIM_SETCLOCK */
putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
/* Enable STM32_TIM_SETMODE*/
putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P |
ATIM_CCER_CC2E | ATIM_CCER_CC2P |
ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET));
stm32_configgpio(GPIO_TIM1_CH1);
stm32_configgpio(GPIO_TIM1_CH2);
stm32_configgpio(GPIO_TIM1_CH3);
/* master output enable = on */
putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET)));
}
long p = freqs == 0 ? p1s : p1s / freqs;
putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET));
putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
if (freqs == 0) {
val &= ~ATIM_CR1_CEN;
} else {
val |= ATIM_CR1_CEN;
}
putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
}
-37
View File
@@ -1,37 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* 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.
*
****************************************************************************/
__BEGIN_DECLS
void rgb_led(int r, int g, int b, int freqs);
__END_DECLS
-48
View File
@@ -1,48 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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>
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::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin2}),
}),
initSPIBusExternal(SPI::Bus::SPI2, {
initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin12}),
initSPIConfigExternal(SPI::CS{GPIO::PortC, GPIO::Pin13}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
@@ -1,54 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2012 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>
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer2, DMA{DMA::Index1, DMA::Stream7, DMA::Channel3}),
initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}),
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortB, GPIO::Pin10}),
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel1}, {GPIO::PortB, GPIO::Pin4}),
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortB, GPIO::Pin5}),
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}),
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortB, GPIO::Pin7}),
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);
@@ -1,17 +0,0 @@
# UAVCAN boot loadable Module ID
set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR})
set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR})
add_definitions(
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
)
set(uavcanblid_hw_version_major 0)
set(uavcanblid_hw_version_minor 83)
set(uavcanblid_name "\"org.auterion.cannode\"")
add_definitions(
-DHW_UAVCAN_NAME=${uavcanblid_name}
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
)
+3 -6
View File
@@ -15,19 +15,15 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
@@ -51,7 +47,8 @@ CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_MODULES_FW_MODE_MANAGER=y
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
@@ -30,7 +30,7 @@ CONFIG_ARM_MPU=y
CONFIG_ARM_MPU_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_LOOPSPERMSEC=115000
CONFIG_BOARD_LOOPSPERMSEC=114325
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_CDCACM=y
@@ -73,7 +73,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=2048
CONFIG_IMXRT_DTCM_HEAP=y
CONFIG_IMXRT_EDMA=y
CONFIG_IMXRT_EDMA_EDBG=y
CONFIG_IMXRT_EDMA_ELINK=y
@@ -141,7 +140,6 @@ CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MM_REGIONS=2
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
@@ -1,5 +1,5 @@
/****************************************************************************
* boards/nxp/tropic-community/nuttx-config/scripts/script.ld
* boards/arm/imxrt/teensy-4.x/scripts/flash.ld
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
@@ -67,7 +67,6 @@ SECTIONS
_sitcmfuncs = ABSOLUTE(.);
FILL(0xFF)
. = 0x40 ;
*(.ram_vectors)
INCLUDE "itcm_static_functions.ld"
INCLUDE "itcm_functions_includes.ld"
. = ALIGN(8);
@@ -76,6 +75,19 @@ SECTIONS
_fitcmfuncs = LOADADDR(.itcmfunc);
/* The RAM vector table (if present) should lie at the beginning of SRAM */
.ram_vectors (COPY) : {
*(.ram_vectors)
} > dtcm
/* Workaround for ethernet issue, by placing g_desc_pool into DTCM,
which effectively puts it into a no-cache region */
.dtcm : {
*(.bss.g_desc_pool)
} > dtcm
.text :
{
_stext = ABSOLUTE(.);
-54
View File
@@ -956,59 +956,5 @@
"type": "PageNotLinkedInternally",
"fileRelativeToRoot": "en\\config\\_autotune.md",
"hideReason": "Page is intended to be an orphan"
},
{
"type": "UrlToLocalSite",
"fileRelativeToRoot": "en\\computer_vision\\path_planning_interface.md",
"link": {
"url": "https://docs.px4.io/v1.14/en/computer_vision/path_planning_interface.html",
"text": "PX4 v1.14 docs"
},
"hideReason": "Intended"
},
{
"type": "UrlToLocalSite",
"fileRelativeToRoot": "en\\dev_log\\log_encryption.md",
"link": {
"url": "https://docs.px4.io/v1.15/en/dev_log/log_encryption.html",
"text": "Log Encryption (PX4 v1.15)"
},
"hideReason": "Intended"
},
{
"type": "UrlToLocalSite",
"fileRelativeToRoot": "en\\releases\\1.16.md",
"link": {
"url": "https://docs.px4.io/main/en/releases/main.html",
"text": "See the latest version"
},
"hideReason": "intended"
},
{
"type": "UrlToLocalSite",
"fileRelativeToRoot": "en\\releases\\main.md",
"link": {
"url": "https://docs.px4.io/main/en/releases/main.html",
"text": "See the latest version"
},
"hideReason": "intended"
},
{
"type": "UrlToLocalSite",
"fileRelativeToRoot": "en\\robotics\\index.md",
"link": {
"url": "https://docs.px4.io/v1.12/en/robotics/dronekit.html",
"text": "PX4 v1.12 > DroneKit"
},
"hideReason": "Intended"
},
{
"type": "UrlToLocalSite",
"fileRelativeToRoot": "en\\ros2\\user_guide.md",
"link": {
"url": "https://docs.px4.io/v1.13/en/ros/ros2_comm.html",
"text": "PX4 v1.13 Docs"
},
"hideReason": "intended"
}
]
File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 415 KiB

+2 -6
View File
@@ -456,7 +456,6 @@
- [Vehicles](sim_gazebo_gz/vehicles.md)
- [Advanced Lift Drag Tool](sim_gazebo_gz/tools_avl_automation.md)
- [Worlds](sim_gazebo_gz/worlds.md)
- [Plugins](sim_gazebo_gz/plugins.md)
- [Gazebo Models Repository](sim_gazebo_gz/gazebo_models.md)
- [Multi-Vehicle Sim](sim_gazebo_gz/multi_vehicle_simulation.md)
- [Gazebo Classic Simulation](sim_gazebo_classic/index.md)
@@ -722,15 +721,13 @@
- [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md)
- [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](mavlink/index.md)
- [MAVLink Messaging](middleware/mavlink.md)
- [Adding Messages](mavlink/adding_messages.md)
- [Streaming Messages](mavlink/streaming_messages.md)
- [Receiving Messages](mavlink/receiving_messages.md)
- [Custom MAVLink Messages](mavlink/custom_messages.md)
- [Protocols/Microservices](mavlink/protocols.md)
- [Standard Modes Protocol](mavlink/standard_modes.md)
- [Standard Modes Protocol](mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md)
- [UORB Bridged to ROS 2](middleware/dds_topics.md)
- [Modules & Commands](modules/modules_main.md)
- [Autotune](modules/modules_autotune.md)
- [Commands](modules/modules_command.md)
@@ -856,7 +853,6 @@
- [Licenses](contribute/licenses.md)
- [Releases](releases/index.md)
- [main (alpha)](releases/main.md)
- [1.16 (release candidate)](releases/1.16.md)
- [1.15 (stable)](releases/1.15.md)
- [1.14](releases/1.14.md)
- [1.13](releases/1.13.md)
+8 -19
View File
@@ -457,7 +457,6 @@
- [Vehicles](/sim_gazebo_gz/vehicles.md)
- [Advanced Lift Drag Tool](/sim_gazebo_gz/tools_avl_automation.md)
- [Worlds](/sim_gazebo_gz/worlds.md)
- [Plugins](/sim_gazebo_gz/plugins.md)
- [Gazebo Models Repository](/sim_gazebo_gz/gazebo_models.md)
- [Multi-Vehicle Sim](/sim_gazebo_gz/multi_vehicle_simulation.md)
- [Gazebo Classic Simulation](/sim_gazebo_classic/index.md)
@@ -490,17 +489,12 @@
- [Versioned](/msg_docs/versioned_messages.md)
- [ActuatorMotors](/msg_docs/ActuatorMotors.md)
- [ActuatorServos](/msg_docs/ActuatorServos.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [ArmingCheckReply](/msg_docs/ArmingCheckReply.md)
- [ArmingCheckRequest](/msg_docs/ArmingCheckRequest.md)
- [BatteryStatus](/msg_docs/BatteryStatus.md)
- [ConfigOverrides](/msg_docs/ConfigOverrides.md)
- [FixedWingLateralSetpoint](/msg_docs/FixedWingLateralSetpoint.md)
- [FixedWingLongitudinalSetpoint](/msg_docs/FixedWingLongitudinalSetpoint.md)
- [GotoSetpoint](/msg_docs/GotoSetpoint.md)
- [HomePosition](/msg_docs/HomePosition.md)
- [LateralControlConfiguration](/msg_docs/LateralControlConfiguration.md)
- [LongitudinalControlConfiguration](/msg_docs/LongitudinalControlConfiguration.md)
- [ManualControlSetpoint](/msg_docs/ManualControlSetpoint.md)
- [ModeCompleted](/msg_docs/ModeCompleted.md)
- [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md)
@@ -529,8 +523,10 @@
- [ActuatorTest](/msg_docs/ActuatorTest.md)
- [AdcReport](/msg_docs/AdcReport.md)
- [Airspeed](/msg_docs/Airspeed.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [AirspeedWind](/msg_docs/AirspeedWind.md)
- [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md)
- [Buffer128](/msg_docs/Buffer128.md)
- [ButtonEvent](/msg_docs/ButtonEvent.md)
- [CameraCapture](/msg_docs/CameraCapture.md)
- [CameraStatus](/msg_docs/CameraStatus.md)
@@ -569,9 +565,6 @@
- [FailsafeFlags](/msg_docs/FailsafeFlags.md)
- [FailureDetectorStatus](/msg_docs/FailureDetectorStatus.md)
- [FigureEightStatus](/msg_docs/FigureEightStatus.md)
- [FixedWingLateralGuidanceStatus](/msg_docs/FixedWingLateralGuidanceStatus.md)
- [FixedWingLateralStatus](/msg_docs/FixedWingLateralStatus.md)
- [FixedWingRunwayControl](/msg_docs/FixedWingRunwayControl.md)
- [FlightPhaseEstimation](/msg_docs/FlightPhaseEstimation.md)
- [FollowTarget](/msg_docs/FollowTarget.md)
- [FollowTargetEstimator](/msg_docs/FollowTargetEstimator.md)
@@ -624,6 +617,7 @@
- [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md)
- [NavigatorStatus](/msg_docs/NavigatorStatus.md)
- [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md)
- [NpfgStatus](/msg_docs/NpfgStatus.md)
- [ObstacleDistance](/msg_docs/ObstacleDistance.md)
- [OffboardControlMode](/msg_docs/OffboardControlMode.md)
- [OnboardComputerStatus](/msg_docs/OnboardComputerStatus.md)
@@ -659,12 +653,13 @@
- [RcParameterMap](/msg_docs/RcParameterMap.md)
- [RoverAttitudeSetpoint](/msg_docs/RoverAttitudeSetpoint.md)
- [RoverAttitudeStatus](/msg_docs/RoverAttitudeStatus.md)
- [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md)
- [RoverMecanumGuidanceStatus](/msg_docs/RoverMecanumGuidanceStatus.md)
- [RoverMecanumSetpoint](/msg_docs/RoverMecanumSetpoint.md)
- [RoverMecanumStatus](/msg_docs/RoverMecanumStatus.md)
- [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md)
- [RoverRateStatus](/msg_docs/RoverRateStatus.md)
- [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md)
- [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md)
- [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md)
- [RoverVelocityStatus](/msg_docs/RoverVelocityStatus.md)
- [Rpm](/msg_docs/Rpm.md)
- [RtlStatus](/msg_docs/RtlStatus.md)
@@ -696,7 +691,6 @@
- [TelemetryStatus](/msg_docs/TelemetryStatus.md)
- [TiltrotorExtraControls](/msg_docs/TiltrotorExtraControls.md)
- [TimesyncStatus](/msg_docs/TimesyncStatus.md)
- [TrajectorySetpoint6dof](/msg_docs/TrajectorySetpoint6dof.md)
- [TransponderReport](/msg_docs/TransponderReport.md)
- [TuneControl](/msg_docs/TuneControl.md)
- [UavcanParameterRequest](/msg_docs/UavcanParameterRequest.md)
@@ -720,18 +714,14 @@
- [WheelEncoders](/msg_docs/WheelEncoders.md)
- [Wind](/msg_docs/Wind.md)
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md)
- [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](/mavlink/index.md)
- [MAVLink Messaging](/middleware/mavlink.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Protocols/Microservices](/mavlink/protocols.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [UORB Bridged to ROS 2](/middleware/dds_topics.md)
- [Modules & Commands](/modules/modules_main.md)
- [Autotune](/modules/modules_autotune.md)
- [Commands](/modules/modules_command.md)
@@ -857,7 +847,6 @@
- [Licenses](/contribute/licenses.md)
- [Releases](/releases/index.md)
- [main (alpha)](/releases/main.md)
- [1.16 (release candidate)](/releases/1.16.md)
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
@@ -212,7 +212,7 @@ The steps are:
type: px4_msgs::msg::ObstacleDistance
```
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)_.
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in _uXRCE-DDS (PX4-ROS 2/DDS Bridge)_.
3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section.
In the **Script Editor** tab, add following scripts in the appropriate sections:
+3 -3
View File
@@ -94,13 +94,13 @@ Exporting the messages allows ROS 2 and the uXRCE-DDS agent to be independent of
While `px4_msgs` has messages for all uORB topics in PX4, not all messages in `px4_msgs` are available to ROS 2/PlotJuggler by default.
The set that are available must be built into the client running on PX4.
These are defined in [dds_topics.yaml](../middleware/dds_topics.md).
These are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The instructions below explain the changes needed to monitor topics that are not available by default.
### Missing Topics
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](../middleware/dds_topics.md) ([source](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) to include the topic and rebuild PX4.
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) to include the topic and rebuild PX4.
If working with real hardware you will need to build and [install](../config/firmware.md#installing-px4-main-beta-or-custom-firmware) custom firmware after changing the YAML file.
@@ -120,7 +120,7 @@ cd ~/ros2_ws/ && colcon build
### Custom Topics
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](../middleware/dds_topics.md), and export the new message into your ROS 2 workspace.
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and export the new message into your ROS 2 workspace.
## See also
+2 -1
View File
@@ -126,7 +126,8 @@ In EKF2 mode, the replay will automatically create the ORB publisher rules descr
To perform an EKF2 replay:
- Record the original log with `SDLOG_MODE` set to `1` to log from boot.
- Record the original log.
Optionally set `SDLOG_MODE` to `1` to log from boot.
- In addition to the `replay` environment variable, set `replay_mode` to `ekf2`:
+1 -1
View File
@@ -12,7 +12,7 @@ To use it you will need to build firmware with this feature enabled and then upl
:::
::: tip
Log encryption was has been improved in PX4 v1.16 to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key).
Log encryption was has been improved in PX4 main (v1.16+) to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key).
In earlier versions the encrypted symmetric key was stored in a separate file.
For more information see the [Log Encryption (PX4 v1.15)](https://docs.px4.io/v1.15/en/dev_log/log_encryption.html).
+5 -5
View File
@@ -1,6 +1,4 @@
# Holybro Kakute H743-Wing
<Badge type="tip" text="PX4 v1.16" />
# Holybro Kakute H7 V2
:::warning
PX4 does not manufacture this (or any) autopilot.
@@ -35,7 +33,9 @@ The board can be bought from one of the following shops (for example):
| Buz-, Buz+ | Piezo buzzer | |
| M1 to M14 | Motor signal outputs | |
## PX4 Bootloader Update {#bootloader}
<a id="bootloader"></a>
## PX4 Bootloader Update
The board comes pre-installed with [Betaflight](https://github.com/betaflight/betaflight/wiki).
Before the PX4 firmware can be installed, the _PX4 bootloader_ must be flashed.
@@ -52,7 +52,7 @@ make holybro_kakuteh7-wing_default
## Installing PX4 Firmware
::: info
KakuteH7-wing is supported in PX4 v1.16 or newer.
KakuteH7-wing is supported with PX4 master & PX4 v1.16 or newer..
Prior to that release you will need to manually build and install the firmware.
:::
+1 -1
View File
@@ -135,7 +135,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS
#### Mission commands
The following commands can be used in missions at time of writing (PX4 v1.16):
The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`):
| QGC mission item | Command | Description |
| ------------------- | ------------------------------------------------------------ | ------------------------------------------------- |
+1 -1
View File
@@ -114,7 +114,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS
#### Mission commands
The following commands can be used in missions at time of writing (PX4 v1.16):
The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`):
| QGC mission item | Command | Description |
| ------------------- | ------------------------------------------------------------------------------ | ---------------------------------------------------------------- |
+1 -1
View File
@@ -139,7 +139,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS
#### Mission commands
The following commands can be used in missions at time of writing (PX4 v1.16):
The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`):
| QGC mission item | Command | Description |
| ------------------- | ------------------------------------------------------------------------------ | ---------------------------------------------------------------- |
+1 -1
View File
@@ -1,6 +1,6 @@
# Ackermann Rovers
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" /> <Badge type="warning" text="Experimental" />
An _Ackermann rover_ controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates.
This kind of steering is used on most commercial vehicles, including cars, trucks etc.
+1 -1
View File
@@ -1,6 +1,6 @@
# Differential Rovers
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" /> <Badge type="warning" text="Experimental" />
A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate.
Forward motion is achieved by driving both wheels at the same speed in the same direction.
+1 -1
View File
@@ -1,6 +1,6 @@
# Mecanum Rovers
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" /> <Badge type="warning" text="Experimental" />
A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first.
Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place.
-89
View File
@@ -1,89 +0,0 @@
# MAVLink Messaging
[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem.
PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on.
This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices.
It also links instructions for how you can add PX4 support for:
- [Adding Standard Messages](../mavlink/adding_messages.md)
- [Streaming MAVLink messages](../mavlink/streaming_messages.md)
- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md)
- [Custom MAVLink Messages](../mavlink/custom_messages.md)
- [Protocols/Microservices](../mavlink/protocols.md)
::: info
We do not yet cover _command_ handling and sending, or how to implement your own microservices.
:::
## MAVLink Overview
MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links.
_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data.
They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement.
Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate.
[Microservices](../mavlink/protocols.md) are "meta protocols" built on top of MAVLink messages.
They are used to communicate information that cannot be sent in a single message.
For example, the [Command Protocol](https://mavlink.io/en/services/command.html) is a service for sending commands that may need acknowledgement and retransmission (quality of service).
Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values.
The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`.
The command is automatically resent a number of times if no acknowledgment is received.
Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4.
Others services include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html), [Parameter Protocol](https://mavlink.io/en/services/parameter.html), and [Mission Protocol](https://mavlink.io/en/services/mission.html).
For more information on what PX4 supports see [Microservices](../mavlink/protocols.md).
MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html).
The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages.
Note that most generated libraries do not create code to implement microservices.
The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them):
- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard.
The definitions move to `common.xml` if accepted following testing.
- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases.
These are supported by many flight stacks, ground stations, and MAVLink peripherals.
Flight stacks that use these definitions are more likely to interoperate.
- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard.
They are present on the vast majority of flight stacks and implemented in the same way.
- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation.
The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder.
The protocol relies on each end of the communication having a shared definition of what messages are being sent.
What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition.
<!--
The messages are sent over-the-wire in the "payload" of a [MAVLink packet](https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format).
In order to reduce the amount of information that must be sent, the packet does not include the message metadata, such as what fields are in the message and so on.
Instead, the fields are serialized in a predefined order based on data size and XML definition order, and MAVLink relies on each end of the communication having a shared definition of what messages are being sent.
The shared identity of the message is conveyed by the message id, along with a CRC ("`CRC_EXTRA`") that uniquely identifies the message based on its name and id, and the field names and types.
The receiving end of the communication will discard any packet for which the message id and the `CRC_EXTRA` do not match.
-->
## PX4 and MAVLink
PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras.
In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards.
::: info
To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`).
During development you can use definitions in `development.xml`.
You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions.
:::
PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink).
This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/).
The build toolchain generates the MAVLink 2 C header files at build time.
The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`:
- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36).
You can change this to any other definition file, but the file must include `common.xml`.
- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)).
The files are generated into the build directory: `/build/<build target>/mavlink/`.
-51
View File
@@ -1,51 +0,0 @@
# MAVLink Microservices (Protocols)
MAVLink "microservices" are a protocols that use multiple messages exchanged between components to communicate more complicated information.
For example, the [Command Protocol](https://mavlink.io/en/services/command.html) provides an efficient mechanism for packaging a command in a (particular) message and receiving acknowledgement of the command in another message.
MAVLink microservices are documented the [MAVLink Guide](https://mavlink.io/en/services/) (this is not exhaustive: not all messages are grouped into protocols and not all protocols are documented).
This section lists the services known to be supported/not supported by PX4 in this version.
## Supported Microservices
These services are known to be supported in some form:
- [Battery Protocol](https://mavlink.io/en/services/battery.html)
- [BATTERY_STATUS](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) and [BATTERY_INFO](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) are streamed.
- Camera Protocols
- [Camera Protocol v2](https://mavlink.io/en/services/camera.html)
- [Camera Definition](https://mavlink.io/en/services/camera_def.html)
- [Command Protocol](https://mavlink.io/en/services/command.html)
- [Component Metadata Protocol](https://mavlink.io/en/services/component_information.html)
- [Events Interface](https://mavlink.io/en/services/events.html)
- [File Transfer Protocol (FTP)](https://mavlink.io/en/services/ftp.html)
- Gimbal Protocols
- [Gimbal Protocol v2](https://mavlink.io/en/services/gimbal_v2.html)
- Can be enabled by [Gimbal Configuration](../advanced/gimbal_control.md#mavlink-gimbal-mnt-mode-out-mavlink)
- PX4 an act as a MAVLink Gimbal for one FC-connected Gimbal
- [Heartbeat/Connection Protocol](https://mavlink.io/en/services/heartbeat.html)
- [High Latency Protocol](https://mavlink.io/en/services/high_latency.html) — PX4 streams [HIGH_LATENCY2](https://mavlink.io/en/messages/common.html#HIGH_LATENCY2)
- [Image Transmission Protocol](https://mavlink.io/en/services/image_transmission.html)
- [Landing Target Protocol](https://mavlink.io/en/services/landing_target.html)
- [Manual Control (Joystick) Protocol](https://mavlink.io/en/services/manual_control.html)
- [MAVLink Id Assignment (sysid, compid)](https://mavlink.io/en/services/mavlink_id_assignment.html)
- [Mission Protocol](https://mavlink.io/en/services/mission.html)
- [Offboard Control Protocol](https://mavlink.io/en/services/offboard_control.html)
- [Remote ID](../peripherals/remote_id.md) ([Open Drone ID Protocol](https://mavlink.io/en/services/opendroneid.html))
- [Parameter Protocol](https://mavlink.io/en/services/parameter.html)
- [Parameter Protocol Extended](https://mavlink.io/en/services/parameter_ext.html) — Allows setting string parameters. Used for setting string parameters set in camera definition files.
- [Payload Protocol](https://mavlink.io/en/services/payload.html)
- [Ping Protocol](https://mavlink.io/en/services/ping.html)
- [Standard Modes Protocol](../mavlink/standard_modes.md)
- [Terrain Protocol](https://mavlink.io/en/services/terrain.html)
- [Time Synchronization](https://mavlink.io/en/services/timesync.html)
- [Traffic Management (UTM/ADS-B)](https://mavlink.io/en/services/traffic_management.html)
- [Arm Authorization Protocol](https://mavlink.io/en/services/arm_authorization.html)
## Unsupported
These services are not supported/used by PX4:
- [Illuminator Protocol](https://mavlink.io/en/services/illuminator.html)
- [Tunnel Protocol](https://mavlink.io/en/services/tunnel.html)
-276
View File
@@ -1,276 +0,0 @@
# dds_topics.yaml — PX4 Topics Exposed to ROS 2
::: info
This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
## Publications
Topic | Type| Rate Limit
--- | --- | ---
`/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) |
`/fmu/out/arming_check_request` | [px4_msgs::msg::ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) | 5.0
`/fmu/out/mode_completed` | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) | 50.0
`/fmu/out/battery_status` | [px4_msgs::msg::BatteryStatus](../msg_docs/BatteryStatus.md) | 1.0
`/fmu/out/collision_constraints` | [px4_msgs::msg::CollisionConstraints](../msg_docs/CollisionConstraints.md) | 50.0
`/fmu/out/estimator_status_flags` | [px4_msgs::msg::EstimatorStatusFlags](../msg_docs/EstimatorStatusFlags.md) | 5.0
`/fmu/out/failsafe_flags` | [px4_msgs::msg::FailsafeFlags](../msg_docs/FailsafeFlags.md) | 5.0
`/fmu/out/manual_control_setpoint` | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) | 25.0
`/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) |
`/fmu/out/position_setpoint_triplet` | [px4_msgs::msg::PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) | 5.0
`/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) |
`/fmu/out/timesync_status` | [px4_msgs::msg::TimesyncStatus](../msg_docs/TimesyncStatus.md) | 10.0
`/fmu/out/vehicle_land_detected` | [px4_msgs::msg::VehicleLandDetected](../msg_docs/VehicleLandDetected.md) | 5.0
`/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) |
`/fmu/out/vehicle_control_mode` | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) | 50.0
`/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) |
`/fmu/out/vehicle_global_position` | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) | 50.0
`/fmu/out/vehicle_gps_position` | [px4_msgs::msg::SensorGps](../msg_docs/SensorGps.md) | 50.0
`/fmu/out/vehicle_local_position` | [px4_msgs::msg::VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) | 50.0
`/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
`/fmu/out/vehicle_status` | [px4_msgs::msg::VehicleStatus](../msg_docs/VehicleStatus.md) | 5.0
`/fmu/out/airspeed_validated` | [px4_msgs::msg::AirspeedValidated](../msg_docs/AirspeedValidated.md) | 50.0
`/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) |
`/fmu/out/home_position` | [px4_msgs::msg::HomePosition](../msg_docs/HomePosition.md) | 5.0
## Subscriptions
Topic | Type
--- | ---
/fmu/in/register_ext_component_request | [px4_msgs::msg::RegisterExtComponentRequest](../msg_docs/RegisterExtComponentRequest.md)
/fmu/in/unregister_ext_component | [px4_msgs::msg::UnregisterExtComponent](../msg_docs/UnregisterExtComponent.md)
/fmu/in/config_overrides_request | [px4_msgs::msg::ConfigOverrides](../msg_docs/ConfigOverrides.md)
/fmu/in/arming_check_reply | [px4_msgs::msg::ArmingCheckReply](../msg_docs/ArmingCheckReply.md)
/fmu/in/message_format_request | [px4_msgs::msg::MessageFormatRequest](../msg_docs/MessageFormatRequest.md)
/fmu/in/mode_completed | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md)
/fmu/in/config_control_setpoints | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md)
/fmu/in/distance_sensor | [px4_msgs::msg::DistanceSensor](../msg_docs/DistanceSensor.md)
/fmu/in/manual_control_input | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md)
/fmu/in/offboard_control_mode | [px4_msgs::msg::OffboardControlMode](../msg_docs/OffboardControlMode.md)
/fmu/in/onboard_computer_status | [px4_msgs::msg::OnboardComputerStatus](../msg_docs/OnboardComputerStatus.md)
/fmu/in/obstacle_distance | [px4_msgs::msg::ObstacleDistance](../msg_docs/ObstacleDistance.md)
/fmu/in/sensor_optical_flow | [px4_msgs::msg::SensorOpticalFlow](../msg_docs/SensorOpticalFlow.md)
/fmu/in/goto_setpoint | [px4_msgs::msg::GotoSetpoint](../msg_docs/GotoSetpoint.md)
/fmu/in/telemetry_status | [px4_msgs::msg::TelemetryStatus](../msg_docs/TelemetryStatus.md)
/fmu/in/trajectory_setpoint | [px4_msgs::msg::TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md)
/fmu/in/vehicle_attitude_setpoint | [px4_msgs::msg::VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md)
/fmu/in/vehicle_mocap_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md)
/fmu/in/vehicle_rates_setpoint | [px4_msgs::msg::VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md)
/fmu/in/vehicle_visual_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md)
/fmu/in/vehicle_command | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md)
/fmu/in/vehicle_command_mode_executor | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md)
/fmu/in/vehicle_thrust_setpoint | [px4_msgs::msg::VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md)
/fmu/in/vehicle_torque_setpoint | [px4_msgs::msg::VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md)
/fmu/in/actuator_motors | [px4_msgs::msg::ActuatorMotors](../msg_docs/ActuatorMotors.md)
/fmu/in/actuator_servos | [px4_msgs::msg::ActuatorServos](../msg_docs/ActuatorServos.md)
/fmu/in/aux_global_position | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md)
/fmu/in/fixed_wing_longitudinal_setpoint | [px4_msgs::msg::FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)
/fmu/in/fixed_wing_lateral_setpoint | [px4_msgs::msg::FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md)
/fmu/in/longitudinal_control_configuration | [px4_msgs::msg::LongitudinalControlConfiguration](../msg_docs/LongitudinalControlConfiguration.md)
/fmu/in/lateral_control_configuration | [px4_msgs::msg::LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md)
## Subscriptions Multi
None
## Not Exported
These messages are not listed in the yaml file.
They are not build into the module, and hence are neither published or subscribed.
::: details See messages
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [EventV0](../msg_docs/EventV0.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [GimbalDeviceAttitudeStatus](../msg_docs/GimbalDeviceAttitudeStatus.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [InputRc](../msg_docs/InputRc.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [Event](../msg_docs/Event.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [Ping](../msg_docs/Ping.md)
- [LedControl](../msg_docs/LedControl.md)
- [Wind](../msg_docs/Wind.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [Gripper](../msg_docs/Gripper.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [LandingGear](../msg_docs/LandingGear.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [RoverVelocitySetpoint](../msg_docs/RoverVelocitySetpoint.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [Rpm](../msg_docs/Rpm.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [EscReport](../msg_docs/EscReport.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [TransponderReport](../msg_docs/TransponderReport.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [Mission](../msg_docs/Mission.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
:::
+87 -1
View File
@@ -1 +1,87 @@
<Redirect to="../mavlink/" />
# MAVLink Messaging
[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem.
PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on.
This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices.
It also links instructions for how you can add PX4 support for:
- [Adding Standard Messages](../mavlink/adding_messages.md)
- [Streaming MAVLink messages](../mavlink/streaming_messages.md)
- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md)
- [Custom MAVLink Messages](../mavlink/custom_messages.md)
::: info
We do not yet cover _command_ handling and sending, or how to implement your own microservices.
:::
## MAVLink Overview
MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links.
_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data.
They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement.
Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate.
The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement.
Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values.
The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`.
The command is resent automatically if no acknowledgment is received.
Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4.
[Microservices](https://mavlink.io/en/services/) are other higher level protocols built on top of MAVLink messages.
They are used to communicate information that cannot be sent in a single message, and to deliver features such as reliable communication.
The command protocol described above is one such service.
Others include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html) and [Mission Protocol](https://mavlink.io/en/services/mission.html).
MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html).
The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages.
Note that most generated libraries do not create code to implement microservices.
The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them):
- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard.
The definitions move to `common.xml` if accepted following testing.
- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases.
These are supported by many flight stacks, ground stations, and MAVLink peripherals.
Flight stacks that use these definitions are more likely to interoperate.
- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard.
They are present on the vast majority of flight stacks and implemented in the same way.
- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation.
The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder.
The protocol relies on each end of the communication having a shared definition of what messages are being sent.
What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition.
<!--
The messages are sent over-the-wire in the "payload" of a [MAVLink packet](https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format).
In order to reduce the amount of information that must be sent, the packet does not include the message metadata, such as what fields are in the message and so on.
Instead, the fields are serialized in a predefined order based on data size and XML definition order, and MAVLink relies on each end of the communication having a shared definition of what messages are being sent.
The shared identity of the message is conveyed by the message id, along with a CRC ("`CRC_EXTRA`") that uniquely identifies the message based on its name and id, and the field names and types.
The receiving end of the communication will discard any packet for which the message id and the `CRC_EXTRA` do not match.
-->
## PX4 and MAVLink
PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras.
In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards.
::: info
To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`).
During development you can use definitions in `development.xml`.
You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions.
:::
PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink).
This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/).
The build toolchain generates the MAVLink 2 C header files at build time.
The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`:
- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36).
You can change this to any other definition file, but the file must include `common.xml`.
- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)).
The files are generated into the build directory: `/build/<build target>/mavlink/`.
+7 -26
View File
@@ -61,12 +61,12 @@ For example the [VelocityLimits](../msg_docs/VelocityLimits.md) message definiti
```text
# Velocity and yaw rate limits for a multicopter position slow mode only
uint64 timestamp # [us] Time since system start.
uint64 timestamp # time since system start (microseconds)
# absolute speeds, NAN means use default limit
float32 horizontal_velocity # [m/s] Horizontal velocity.
float32 vertical_velocity # [m/s] Vertical velocity.
float32 yaw_rate # [rad/s] Yaw rate.
float32 horizontal_velocity # [m/s]
float32 vertical_velocity # [m/s]
float32 yaw_rate # [rad/s]
```
By default this message definition will be compiled to a single topic with an id `velocity_limits`, a direct conversion from the CamelCase name to a snake_case version.
@@ -92,34 +92,15 @@ To nest a message, simply include the nested message type in the parent message
```text
# Global position setpoint triplet in WGS84 coordinates.
#
# This are the three next waypoints (or just the next two or one).
uint64 timestamp # [us] Time since system start.
uint64 timestamp # time since system start (microseconds)
PositionSetpoint previous
PositionSetpoint current
PositionSetpoint next
```
### uORB Buffer Length (ORB_QUEUE_LENGTH)
uORB messages have a single-message buffer by default, which may be overwritten if the message publication rate is too high.
In most cases this does not matter: either we are only interested in the latest sample of a topic, such as a sensor value or a setpoint, or losing a few samples is not a particular problem.
For relatively few cases, such as vehicle commands, it is important that we don't drop topics.
In order to reduce the chance that messages will be dropped we can use named constant `ORB_QUEUE_LENGTH` to create a buffer of the specified length.
For example, to create a four-message queue, add the following line to your message definition:
```sh
uint8 ORB_QUEUE_LENGTH = 4
```
As long as subscribers are able to read messages out of the buffer quickly enough than it isn't ever fully filled to the queue length (by publishers), they will be able to get all messages that are sent.
Messages will still be lost they are published when the queue is filled.
Note that the queue length value must be a power of 2 (so 2, 4, 8, ...).
### Message/Field Deprecation {#deprecation}
As there are external tools using uORB messages from log files, such as [Flight Review](https://github.com/PX4/flight_review), certain aspects need to be considered when updating existing messages:
@@ -135,9 +116,9 @@ As there are external tools using uORB messages from log files, such as [Flight
## Message Versioning
<Badge type="tip" text="PX4 v1.16" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" />
Optional message versioning was introduced PX4 v1.16 to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions.
Optional message versioning was introduced in the `main` branch (planned for PX4 v1.16+) to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions.
Versioned messages are designed to remain more stable over time compared to their non-versioned counterparts, as they are intended to be used across multiple releases of PX4 and external systems, ensuring greater compatibility over longer periods.
Versioned messages include an additional field `uint32 MESSAGE_VERSION = x`, where `x` corresponds to the current version of the message.
+11 -10
View File
@@ -38,7 +38,7 @@ The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is gen
The agent has no dependency on client code.
It can be built standalone or in a ROS 2 workspace, or installed as a snap package on Ubuntu.
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [/src/modules/uxrce_dds_client/dds_topics.yaml](../middleware/dds_topics.md) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
PX4 main or release builds automatically export the set of uORB messages definitions in the build to an associated branch in [PX4/px4_msgs](https://github.com/PX4/px4_msgs).
@@ -320,11 +320,13 @@ ROS_DOMAIN_ID=3 PX4_UXRCE_DDS_PORT=9999 PX4_UXRCE_DDS_NS=drone make px4_sitl gz_
## Supported uORB Messages
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](../middleware/dds_topics.md).
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The topics are release specific (support is compiled into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) at build time).
While most releases should support a very similar set of messages, to be certain you would need to check the yaml file for your particular release.
<!-- Jublish the set we use?: https://github.com/PX4/px4_msgs/issues/22 -->
Note that ROS 2/DDS needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages.
The message definitions are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs), and they are automatically synchronized by CI on the `main` and release branches.
Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics.
@@ -341,20 +343,20 @@ Therefore,
```
::: info
Technically, [dds_topics.yaml](../middleware/dds_topics.md) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [DDS Topics YAML](#dds-topics-yaml) below.
:::
## Customizing the Namespace
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations):
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (which is useful for multi vehicle operations):
- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line.
This technique can be used both in simulation and real vehicles.
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
::: info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#dds-ros-2-services).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#dds-ros-2-services).
Therefore, commands like:
```sh
@@ -411,7 +413,7 @@ Deadline, lifespan, and lease durations are also all set to "default".
## DDS Topics YAML
The PX4 [dds_topics.yaml](../middleware/dds_topics.md) file defines the set of PX4 uORB topics that are built into firmware and published.
The PX4 yaml file [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) defines the set of PX4 uORB topics that are built into firmware and published.
More precisely, it completely defines the relationship/pairing between PX4 uORB and ROS 2 messages.
The file is structured as follows:
@@ -421,17 +423,16 @@ publications:
- topic: /fmu/out/collision_constraints
type: px4_msgs::msg::CollisionConstraints
rate_limit: 50. # Limit max publication rate to 50 Hz
...
- topic: /fmu/out/vehicle_odometry
type: px4_msgs::msg::VehicleOdometry
# Use default publication rate limit of 100 Hz
rate_limit: 150.
- topic: /fmu/out/vehicle_status
type: px4_msgs::msg::VehicleStatus
rate_limit: 5.
rate_limit: 50.
- topic: /fmu/out/vehicle_trajectory_waypoint_desired
type: px4_msgs::msg::VehicleTrajectoryWaypoint
@@ -540,7 +541,7 @@ Take a look at the [client startup section](#starting-the-client) to learn how t
#### New file for setting which topics are published
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topics.yaml](../middleware/dds_topics.md) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topic.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
See [Supported uORB Messages](#supported-uorb-messages) and [DDS Topics YAML](#dds-topics-yaml) sections for more information.
-196
View File
@@ -1,196 +0,0 @@
# PX4-Autopilot v1.16.0 Release Notes
<Badge type="info" text="Candidate Release" />
<script setup>
import { useData } from 'vitepress'
const { site } = useData();
</script>
<div v-if="site.title !== 'PX4 Guide (main)'">
<div class="custom-block danger">
<p class="custom-block-title">This page is on a release branch, and hence possibly out of date. <a href="https://docs.px4.io/main/en/releases/main.html">See the latest version</a>.</p>
</div>
</div>
This document covers all changes in PX4 v1.16.0 since the previous stable release ([PX4 v1.15.0](../releases/1.15.md)).
::: info
These notes include only changes merged in 2023 and later — commits before 2023 are not listed.
:::
## Read Before Upgrading
Please continue reading for [upgrade instructions](#upgrade-guide).
## Major Changes
- **Rover support rework**
- New dedicated firmware build for rovers (airframe IDs 5000052000)
- Separate modules for Ackermann, differential and mecanum rovers, each with manual, acro, stabilized, position and auto modes
- Shared pure-pursuit guidance library for all rover modules
- Legacy rover position control module deprecated in favor of the new modules
## Upgrade Guide
- [PX4-Autopilot#24648](https://github.com/PX4/PX4-Autopilot/pull/24648): Added setting default for EKF2_EV_CTRL to 15 for VOXL 2 boards
- [PX4-Autopilot#22517](https://github.com/PX4/PX4-Autopilot/pull/22517): Change default ethernet IP
- [PX4-Autopilot#24602](https://github.com/PX4/PX4-Autopilot/pull/24602): remove serial port default from sf45 module
## Other changes
### Hardware Support
- **[New Hardware]** [PX4-Autopilot#23830](https://github.com/PX4/PX4-Autopilot/pull/23830): Boards: ARK FPV FC
- **[New Hardware]** [PX4-Autopilot#23414](https://github.com/PX4/PX4-Autopilot/pull/23414): board: add cuav 7-nano
- **[New Hardware]** [PX4-Autopilot#24769](https://github.com/PX4/PX4-Autopilot/pull/24769): add new board corvon743v1
- **[New Hardware]** [PX4-Autopilot#24018](https://github.com/PX4/PX4-Autopilot/pull/24018): boards: bluerobotics: navigator: Add initial support
- **[New Hardware]** [PX4-Autopilot#24147](https://github.com/PX4/PX4-Autopilot/pull/24147): boards: add new board micoair743-v2
- **[New Hardware]** [PX4-Autopilot#23218](https://github.com/PX4/PX4-Autopilot/pull/23218): boards: add new board micoair h743
- **[New Hardware]** [PX4-Autopilot#24512](https://github.com/PX4/PX4-Autopilot/pull/24512): boards: Add FMUv6s target
- **[New Hardware]** [PX4-Autopilot#23927](https://github.com/PX4/PX4-Autopilot/pull/23927): manifest: Add Skynode S baseboard
- **[New Hardware]** [PX4-Autopilot#23257](https://github.com/PX4/PX4-Autopilot/pull/23257): Add Tropic VMU board support (Baseboard for Teensy 4.1)
- **[New Hardware]** [PX4-Autopilot#23697](https://github.com/PX4/PX4-Autopilot/pull/23697): boards: add new board X-MAV AP-H743v2
- **[New Hardware]** [PX4-Autopilot#23551](https://github.com/PX4/PX4-Autopilot/pull/23551): 3DR boards: Support for 3DR Control Zero H7 OEM Rev G
- **[New Hardware]** [PX4-Autopilot#23623](https://github.com/PX4/PX4-Autopilot/pull/23623): new board support ZeroOne x6
### Common
- [Optical flow scaling factor - SENS_FLOW_SCALE](../sensor/optical_flow.md#scale-factor). ([PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936)).
- [PX4-Autopilot#22813](https://github.com/PX4/PX4-Autopilot/pull/22813): Reintroduce optional parameter versioning mechanism for airframe maintainers
- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)).
- [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage.
- Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number).
- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed.
The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)).
- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file.
This makes log decryption much easier, as there is no need to download or identify a separate key file.
([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)).
- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter.
Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires.
This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses.
([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)).
- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850))
- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available.
This typically reduces false warnings due to magnetometer inconsistencies.
([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)).
### Control
- [PX4-Autopilot#23863](https://github.com/PX4/PX4-Autopilot/pull/23863): [Sponsored by ARK] Bidirectional DShot
- [PX4-Autopilot#24196](https://github.com/PX4/PX4-Autopilot/pull/24196): Make control allocation and actuator effectiveness a non-module-specific library
- [PX4-Autopilot#24221](https://github.com/PX4/PX4-Autopilot/pull/24221): Spacecraft Build and Bare Control Allocator
- Configurable multicopter orbit-mode yaw via `MC_ORBIT_YAW_MOD` ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358))
- Collision prevention now works in manual (acceleration-based) flight mode (`MPC_POS_MODE`) ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507))
### Estimation
- [PX4-Autopilot#23854](https://github.com/PX4/PX4-Autopilot/pull/23854): EKF2: ellipsoidal earth navigation
- [PX4-Autopilot#23263](https://github.com/PX4/PX4-Autopilot/pull/23263): EKF2: Terrain state
- [PX4-Autopilot#23185](https://github.com/PX4/PX4-Autopilot/pull/23185): ekf2: add mag type init
- [PX4-Autopilot#23436](https://github.com/PX4/PX4-Autopilot/pull/23436): ekf2: Optical flow enabled by default
- Position-loss failsafe delay removed; triggers 1 s after loss (see Common)
### Sensors
- [PX4-Autopilot#23656](https://github.com/PX4/PX4-Autopilot/pull/23656): Implemented AUAV absolute/differential pressure sensor support
- [PX4-Autopilot#23639](https://github.com/PX4/PX4-Autopilot/pull/23639): Implemented temperature sensor support for INA228 / INA238
- [PX4-Autopilot#22744](https://github.com/PX4/PX4-Autopilot/pull/22744): Add Ublox ZED-F9P-15B
- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Mag cal: automatically disable internal mags if external ones are available
- [PX4-Autopilot#23064](https://github.com/PX4/PX4-Autopilot/pull/23064): BMP581: Add Bosch BMP581 barometer
- [PX4-Autopilot#22914](https://github.com/PX4/PX4-Autopilot/pull/22914): Murata SCH16T IMU driver
- [PX4-Autopilot#23023](https://github.com/PX4/PX4-Autopilot/pull/23023): ST IIS2MDC Magnetometer driver
- [PX4-Autopilot#24121](https://github.com/PX4/PX4-Autopilot/pull/24121): Include distance sensor in dds topics
- [PX4-Autopilot#23925](https://github.com/PX4/PX4-Autopilot/pull/23925): drivers: magnetometer: mmc5983ma: Add SPI support
- [PX4-Autopilot#23909](https://github.com/PX4/PX4-Autopilot/pull/23909): drivers/magnetometer/ak09916: Add support to AK09915
- [PX4-Autopilot#23362](https://github.com/PX4/PX4-Autopilot/pull/23362): Add Bosch BMM350 magnetometer
- [PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316): Compass calibration now disables internal compass when external unit present, reducing false warnings
### Simulation
- **SIH**:
- The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7.
([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)).
- SIH now supports the standard VTOL airframe
([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)).
- **Gazebo**:
- Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4.
The default installer scripts (used for CI) and documentation have been updated.
This is required because Garden end-of-life is Nov 2024.
([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603))
- New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)).
- New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)).
- New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)).
- New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)).
- New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)).
- New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)).
- New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)).
- New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)).
- [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783))
- [PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471): Gazebo: Moving platform
### uXRCE-DDS / ROS2
- **[Feature]** [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): <Badge type="warning" text="Experimental"/> [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically
- [PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582): dds_topics: add vtol_vehicle_status
- [PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583): dds_topics: add home_position
### MAVLink
- TBD
### Multi-Rotor
- [PX4-Autopilot#24173](https://github.com/PX4/PX4-Autopilot/pull/24173): [Multirotor] add yaw torque low pass filter
- [PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943): Add gz model for quadtailsitter
- [PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358): Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD)
- [PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507): Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE).
### VTOL
- TBD
### Fixed-wing
- [PX4-Autopilot#24167](https://github.com/PX4/PX4-Autopilot/pull/24167): Fixedwing: fix wheel controller
- [PX4-Autopilot#23520](https://github.com/PX4/PX4-Autopilot/pull/23520): FixedWing: allow position control without valid global position
- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460)
### Rover
This release contains a major rework for the rover support in PX4:
- Complete restructure of the [rover related documentation](../frames_rover/index.md).
- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build).
- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md):
- The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes).
- New module dedicated to [differential rovers](../frames_rover/differential.md):
- The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes).
- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md):
- The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes).
- Added rover-specific firmware build (`5000052000`) for Ackermann, differential and mecanum rovers
- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)).
This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover):
- Generic Differential Rover `50000`.
- Generic Ackermann Rover `51000`.
- Axial SCX10 2 Trail Honcho `51001`.
- Generic Mecanum Rover `52000`.
- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules.
- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)).
- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules.
### Infrastructure
- [PX4-Autopilot#24011](https://github.com/PX4/PX4-Autopilot/pull/24011): standard_modes: add vehicle-type specific standard modes
- [PX4-Autopilot#24020](https://github.com/PX4/PX4-Autopilot/pull/24020): ci: build all upload to releases
- [PX4-Autopilot#24002](https://github.com/PX4/PX4-Autopilot/pull/24002): ci: px4-dev container
- [PX4-Autopilot#23937](https://github.com/PX4/PX4-Autopilot/pull/23937): ci: workflow for ubuntu 24
- [PX4-Autopilot#23869](https://github.com/PX4/PX4-Autopilot/pull/23869): ci: add test for Ubuntu 22.04
- [PX4-Autopilot#23574](https://github.com/PX4/PX4-Autopilot/pull/23574): ci: try runs-on Dronecode Infra
- [PX4-Autopilot#23550](https://github.com/PX4/PX4-Autopilot/pull/23550): ci: replace build workflows
+1 -2
View File
@@ -2,8 +2,7 @@
A list of PX4 release notes, they contain a list of the changes that went into each release, explaining the included features, bug fixes, deprecations and updates in detail.
- [main](../releases/main.md) (changes since v1.16)
- [v1.16](../releases/1.16.md)
- [main](../releases/main.md) (changes since v1.15)
- [v1.15](../releases/1.15.md)
- [v1.14](../releases/1.14.md)
- [v1.13](../releases/1.13.md)
+63 -10
View File
@@ -9,15 +9,15 @@ const { site } = useData();
<div v-if="site.title !== 'PX4 Guide (main)'">
<div class="custom-block danger">
<p class="custom-block-title">This page is on a release branch, and hence probably out of date. <a href="https://docs.px4.io/main/en/releases/main.html">See the latest version</a>.</p>
<p class="custom-block-title">This page is on a release bramch, and hence probably out of date. <a href="https://docs.px4.io/main/en/releases/main.html">See the latest version</a>.</p>
</div>
</div>
This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)).
This contains changes to PX4 `main` branch since the last major release ([PX v1.15](../releases/1.15.md)).
::: warning
PX4 v1.16 is in candidate-release testing, pending release.
Update these notes with features that are going to be in `main` but not the PX4 v1.16 release.
The PX4 v1.15 release is in beta testing, pending release.
Update these notes with features that are going to be in `main` but not the PX4 v1.15 release.
:::
## Read Before Upgrading
@@ -40,7 +40,22 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Common
- TBD
- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)).
- [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage.
- Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number).
- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed.
The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)).
- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file.
This makes log decryption much easier, as there is no need to download or identify a separate key file.
([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)).
- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter.
Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires.
This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses.
([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)).
- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850))
- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available.
This typically reduces false warnings due to magnetometer inconsistencies.
([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)).
### Control
@@ -56,7 +71,26 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Simulation
- TBD
- [SIH]:
- The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7.
([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)).
- SIH now supports the standard VTOL airframe
([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)).
- [Gazebo]:
- Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4.
The default installer scripts (used for CI) and documentation have been updated.
This is required because Garden end-of-life is Nov 2024.
([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603))
- New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)).
- New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)).
- New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)).
- New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)).
- New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)).
- New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)).
- New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)).
- New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)).
- [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783))
- [Moving platform simulation](../sim_gazebo_gz/worlds#moving-platform) ([PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471))
### Ethernet
@@ -64,7 +98,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### uXRCE-DDS / ROS2
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)).
- **[Feature]** <Badge type="warning" text="Experimental"/> [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically ([PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113))
### MAVLink
@@ -72,7 +106,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Multi-Rotor
- TBD
- Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358))
- Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507)
### VTOL
@@ -80,11 +115,29 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Fixed-wing
- TBD
- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460)
### Rover
- TBD
This release contains a major rework for the rover support in PX4:
- Complete restructure of the [rover related documentation](../frames_rover/index.md).
- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build).
- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md):
- The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes).
- New module dedicated to [differential rovers](../frames_rover/differential.md):
- The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes).
- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md):
- The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes).
- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)).
This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover):
- Generic Differential Rover `50000`.
- Generic Ackermann Rover `51000`.
- Axial SCX10 2 Trail Honcho `51001`.
- Generic Mecanum Rover `52000`.
- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules.
- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)).
- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules.
### ROS 2
+2 -179
View File
@@ -341,7 +341,6 @@ The used types also define the compatibility with different vehicle types.
The following sections provide a list of supported setpoint types:
- [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
- [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints
:::tip
@@ -356,7 +355,7 @@ You can add your own setpoint types by adding a class that inherits from `px4_ro
This setpoint type is currently only supported for multicopters.
:::
Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type.
Smoothly control position and (optionally) heading setpoints with the [px4_ros2::GotoSetpointType](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type.
The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints.
The most trivial use is simply inputting a 3D position into the update method:
@@ -401,137 +400,6 @@ _goto_setpoint->update(
max_heading_rate_rad_s);
```
#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType)
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" />
::: info
This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode.
:::
Use the [`px4_ros2::FwLateralLongitudinalSetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1FwLateralLongitudinalSetpointType.html) to directly control the lateral and longitudinal dynamics of a fixed-wing vehicle — that is, side-to-side motion (turning/banking) and forward/vertical motion (speeding up and climbing/descending), respectively.
This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../modules/modules_controller.md#fw-lat-lon-control), which decouples lateral and longitudinal inputs while ensuring that vehicle limits are respected.
To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided:
1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion.
If both are set to `NAN`, the vehicle will maintain its current altitude.
2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite.
For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)).
##### Basic Usage
This type has a number of update methods, each allowing you to specify an increasing number of setpoints.
The simplest method is `updateWithAltitude()`, which allows you to specify a `course` and `altitude` target setpoint:
```cpp
const float altitude_msl = 500.F;
const float course = 0.F; // due North
_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, course);
```
PX4 uses the setpoints to compute the _roll angle_, _pitch angle_ and _throttle_ setpoints that are sent to lower level controllers.
Note that the commanded flight is expected to be relatively gentle/unaggressive when using this method.
This is done as follows:
- Lateral control output:
course setpoint (set by user) &rarr; airspeed direction (heading) setpoint &rarr; lateral acceleration setpoint &rarr; roll angle setpoint.
- Longitudinal control output:
altitude setpoint (set by user) &rarr; height rate setpoint &rarr; pitch angle setpoint and throttle settings.
The `updateWithHeightRate()` method allows you to set a target `course` and `height_rate` (this is useful if the speed of ascent or descent matters, or needs to be dynamically controlled):
```cpp
const float height_rate = 2.F;
const float course = 0.F; // due North
_fw_lateral_longitudinal_setpoint->updateWithHeightRate(height_rate, course);
```
The `updateWithAltitude()` and `updateWithHeightRate()` methods allow you to additionally control the equivalent airspeed or lateral acceleration by specifying them as the third and fourth arguments, respectively:
```cpp
const float altitude_msl = 500.F;
const float course = 0.F; // due North
const float equivalent_aspd = 15.F; // m/s
const float lateral_acceleration = 2.F; // FRD, used as feedforward
_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl,
course,
equivalent_aspd,
lateral_acceleration);
```
The equivalent airspeed and lateral acceleration arguments are defined as `std::optional<float>`, so you can omit any of them by passing `std::nullopt`.
::: tip
If both lateral acceleration and course setpoints are provided, the lateral acceleration setpoint will be used as feedforward.
:::
##### Full Control Using the Setpoint Struct
For full flexibility, you can create and pass a [`FwLateralLongitudinalSetpoint`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwLateralLongitudinalSetpoint.html) struct.
Each field is templated with `std::optional<float>`.
::: tip
If both course and airspeed direction are set: airspeed direction takes precedence, course is not controlled.
Lateral acceleration is treated as feedforward if either course or airspeed direction are also finite.
If both altitude and height rate are set: height rate takes precedence, altitude is not controlled.
:::
```cpp
px4_ros2::FwLateralLongitudinalSetpoint setpoint_s;
setpoint_s.withCourse(0.F);
// setpoint_s.withAirspeedDirection(0.2F); // uncontrolled
setpoint_s.withLateralAcceleration(2.F); // feedforward
//setpoint_s.withAltitude(500.F); // uncontrolled
setpoint_s.withHeightRate(2.F);
setpoint_s.withEquivalentAirspeed(15.F);
_fw_lateral_longitudinal_setpoint->update(setpoint_s);
```
The diagram below illustrates the interaction between the `FwLateralLongitudinalSetpointType` and PX4 when all inputs are set.
![FW ROS Interaction](../../assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg)
##### Advanced Configuration (Optional)
You can also pass a [`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html) struct along with the setpoint to override default controller settings and constraints such as pitch limits, throttle limits, and target sink/climb rates.
This is intended for advanced users:
```cpp
px4_ros2::FwLateralLongitudinalSetpoint setpoint_s;
setpoint_s.withAirspeedDirection(0.F);
setpoint_s.withLateralAcceleration(2.F); // feedforward
setpoint_s.withAltitude(500.F);
setpoint_s.withEquivalentAirspeed(15.F);
px4_ros2::FwControlConfiguration config_s;
config_s.withTargetClimbRate(3.F);
config_s.withMaxAcceleration(5.F);
config_s.withThrottleLimits(0.4F, 0.6F);
_fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s);
```
All configuration fields are defined as `std::optional<float>`.
Unset values will default to the PX4 configuration.
See [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) and [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md) for more information on configuration options.
:::info
For safety, PX4 automatically limits configuration values to stay within the vehicles constraints.
For example, throttle overrides are clamped to remain between [`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN)
and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX).
:::
#### Direct Actuator Control Setpoint (DirectActuatorsSetpointType)
Actuators can be directly controlled using the [px4_ros2::DirectActuatorsSetpointType](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1DirectActuatorsSetpointType.html) setpoint type.
@@ -543,55 +411,11 @@ For example to control a quadrotor, you need to set the first 4 motors according
If you want to control an actuator that does not control the vehicle's motion, but for example a payload servo, see [below](#controlling-an-independent-actuator-servo).
:::
### Controlling a VTOL
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration:
- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html).
- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype).
As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required.
If you would like to command a VTOL transition in your external mode, you need to use the [VTOL API](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1VTOL.html). The VTOL API provides the functionality to command a transition and query the current state of the vehicle.
Use this API with caution!
Commanding transitions externally makes the user partially responsible for ensuring smooth and safe behavior, unlike onboard transitions (e.g. via RC switch) where PX4 handles the full process:
1. Ensure that both the `TrajectorySetpointType` and the `FwLateralLongitudinalSetpointType` are available to your mode.
2. Create an instance of `px4_ros2::VTOL` in the constructor of your mode.
3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state.
4. During transition, send the following combination of setpoints:
```cpp
// Assuming the instance of the px4_ros2::VTOL object is called vtol
// Send TrajectorySetpointType as follows:
Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition();
Eigen::Vector3f velocity_sp{NAN, NAN, 0.f};
_trajectory_setpoint->update(velocity_sp, acceleration_sp);
// Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired
float course_sp = 0.F; // North
_fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp)
```
This will ensure that the transition is handled properly within PX4.
You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions.
To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object.
See [this external flight mode implementation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol) for a practical example on how to use this API.
### Controlling an Independent Actuator/Servo
If you want to control an independent actuator (a servo), follow these steps:
1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink).
1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink)
2. Create an instance of [px4_ros2::PeripheralActuatorControls](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1PeripheralActuatorControls.html) in the constructor of your mode.
3. Call the `set()` method to control the actuator(s).
This can be done independently of any active setpoints.
@@ -603,7 +427,6 @@ You can access PX4 telemetry topics directly via the following classes:
- [OdometryGlobalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryGlobalPosition.html): Global position
- [OdometryLocalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryLocalPosition.html): Local position, velocity, acceleration, and heading
- [OdometryAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAttitude.html): Vehicle attitude
- [OdometryAirspeed](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAirspeed.html): Airspeed
For example, you can query the vehicle's current position estimate as follows:
@@ -1,6 +1,6 @@
# PX4 ROS 2 Message Translation Node
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" /> <Badge type="warning" text="Experimental" />
The message translation node allows ROS 2 applications that were compiled against different versions of the PX4 messages to interwork with newer versions of PX4, and vice versa, without having to change either the application or the PX4 side.
@@ -207,7 +207,7 @@ Message translations can be either _direct_ or _generic_.
### File Structure
Starting from PX4 v1.16, the PX4-Autopilot `msg/` and `srv/` directories are structured as follows:
Starting from PX4 v1.16 (main), the PX4-Autopilot `msg/` and `srv/` directories are structured as follows:
```
PX4-Autopilot
+5 -5
View File
@@ -28,13 +28,13 @@ The agent acts as a proxy for the client to publish and subscribe to topics in t
The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default.
It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics.
The subset of uORB messages that are generated into the client are specified in [dds_topics.yaml](../middleware/dds_topics.md).
The subset of uORB messages that are generated into the client are listed in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages.
ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware.
You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases).
Starting from PX4 v1.16, in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4.
Starting from PX4 v1.16 (main) in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4.
This requires the [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to be running to ensure that messages can be converted and exchanged correctly.
Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code.
@@ -367,7 +367,7 @@ accelerometer_integral_dt: 4739
#### (Optional) Starting the Translation Node
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" /> <Badge type="tip" /> <Badge type="warning" text="Experimental" />
This example is built with PX4 and ROS2 versions that use the same message definitions.
If you were to use incompatible [message versions](../middleware/uorb.md#message-versioning) you would need to install and run the [Message Translation Node](./px4_ros2_msg_translation_node.md) as well, before running the example:
@@ -394,7 +394,7 @@ To control applications, ROS 2 applications:
- subscribe to (listen to) telemetry topics published by PX4
- publish to topics that cause PX4 to perform some action.
The topics that you can use are defined in [dds_topics.yaml](../middleware/dds_topics.md), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md).
The topics that you can use are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and you can get more information about their data in the [uORB Message Reference](../msg_docs/index.md).
For example, [VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) can be used to get the vehicle global position, while [VehicleCommand](../msg_docs/VehicleCommand.md) can be used to command actions such as takeoff and land.
The [ROS 2 Example applications](#ros-2-example-applications) examples below provide concrete examples of how to use these topics.
@@ -728,7 +728,7 @@ Custom topic and service namespaces can be applied at build time (changing [dds_
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
::: info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#px4-ros-2-service-servers).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#px4-ros-2-service-servers).
Therefore, commands like:
```sh
-5
View File
@@ -392,11 +392,6 @@ As long as the world file and the model file are in the Gazebo search path (`GZ_
However, `make px4_sitl gz_<model>_<world>` won't work with them.
:::
## Extending Gazebo with Plugins
World, vehicle (model), and sensor behaviour can be customised using plugins.
For more information see [Gazebo Plugins](../sim_gazebo_gz/plugins.md).
## Multi-Vehicle Simulation
Multi-Vehicle simulation is supported on Linux hosts.
-91
View File
@@ -1,91 +0,0 @@
# Gazebo Plugins
Gazebo plugins extend the simulator with custom functionality not provided by default. They can be attached to different entity types and allow you to add new sensors, modify world physics, or interact with the simulation environment.
## Plugin Types
Plugins can be attached to these entity types:
- **World** - Global simulation behavior
- **Model** - Specific model functionality
- **Sensor** - Custom sensor implementations
- **Actor** - Dynamic entity behavior
## Supported Plugins
PX4 currently supports these plugins:
- [OpticalFlowSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/optical_flow): Provides optical flow sensor simulation using OpenCV-based flow calculation.
- [GstCameraSystem](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/gstreamer): Streams camera feeds via UDP (RTP/H.264) or RTMP with optional NVIDIA CUDA hardware acceleration.
- [MovingPlatformController](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/moving_platform_controller): Controls moving platforms (ships, trucks, etc.) for takeoff and landing scenarios.
Includes configurable velocity, heading, and random fluctuations.
## Plugin Registration
Plugins must be registered in the [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) file to be available in your world:
```xml
<server_config>
<plugins>
<!-- Core Gazebo systems -->
<plugin entity_name="*" entity_type="world" filename="gz-sim-physics-system" name="gz::sim::systems::Physics"/>
<!-- Custom PX4 plugins -->
<plugin entity_name="*" entity_type="world" filename="libOpticalFlowSystem.so" name="custom::OpticalFlowSystem"/>
<plugin entity_name="*" entity_type="world" filename="libGstCameraSystem.so" name="custom::GstCameraSystem"/>
</plugins>
</server_config>
```
## Creating Custom Plugins
When developing new plugins:
1. **Follow the plugin architecture** - Implement desired interfaces.
You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`.
The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html).
2. **Register your plugin** - Add it to [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) for discovery.
3. **Use the custom namespace** - Follow the pattern `custom::YourPluginName`.
### Example Plugin Structure
```cpp
class YourCustomSystem :
public gz::sim::System,
public gz::sim::ISystemPreUpdate,
public gz::sim::ISystemPostUpdate
{
public:
void PreUpdate(const gz::sim::UpdateInfo &_info,
gz::sim::EntityComponentManager &_ecm) final;
void PostUpdate(const gz::sim::UpdateInfo &_info,
const gz::sim::EntityComponentManager &_ecm) final;
};
// Plugin registration
GZ_ADD_PLUGIN(YourCustomSystem, gz::sim::System,
YourCustomSystem::ISystemPreUpdate,
YourCustomSystem::ISystemPostUpdate)
GZ_ADD_PLUGIN_ALIAS(YourCustomSystem, "custom::YourCustomSystem")
```
## Enabling a Plugin
For world plugins all you need to do is [register the plugin](#plugin-registration) (add it to the `server.config`).
It will then be available to all worlds and vehicles.
The process for adding vehicle model/sensor plugins is not documented.
This can tracked through [PX4-Autopilot#2493](https://github.com/PX4/PX4-Autopilot/issues/24939).
## Resources
- **PX4 Plugins**: [Repository source code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins)
- **Official Gazebo Documentation**: [System Plugins Guide](https://gazebosim.org/api/sim/9/createsystemplugins.html)
- **Server Configuration**: [Configuration Reference](https://gazebosim.org/api/sim/9/server_config.html)
- **PX4 Gazebo-classic Plugins**: [PX4 Gazebo Classic Plugins](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/main/src)
::: info
Plugins for modern Gazebo are still evolving. The plugin system differs from Gazebo Classic.
:::
+1 -1
View File
@@ -75,7 +75,7 @@ World with walls that is designed for testing [collision prevention](../computer
## Moving Platform
<Badge type="tip" text="PX4 v1.16" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" />
[Empty world](#default) with the addition of a flat moving platform, to simulate drone operations from moving vehicles like ships or trucks. The platform is controlled by a plugin which is included in the world. The platform is at a height of 2m, so place the vehicle on it with:
+1 -1
View File
@@ -20,7 +20,7 @@ Operating in the 2.4GHz frequency band, it allows unrestricted global use withou
- **Frequency Band:** 2.4GHz
- **Speed:** Up to 11 Mbps (adjustable)
- **Range:** Up to 1000 meters (varies upon environments)
- **Range:** Up to 500 meters (varies upon environments)
- **Payload Capacity:** Up to 1024 bytes
### Network Schemes
+8 -19
View File
@@ -459,7 +459,6 @@
- [Vehicles](sim_gazebo_gz/vehicles.md)
- [Advanced Lift Drag Tool](sim_gazebo_gz/tools_avl_automation.md)
- [Worlds](sim_gazebo_gz/worlds.md)
- [Plugins](sim_gazebo_gz/plugins.md)
- [Gazebo Models Repository](sim_gazebo_gz/gazebo_models.md)
- [Multi-Vehicle Sim](sim_gazebo_gz/multi_vehicle_simulation.md)
- [Gazebo Classic Simulation](sim_gazebo_classic/index.md)
@@ -492,17 +491,12 @@
- [Versioned](msg_docs/versioned_messages.md)
- [ActuatorMotors](msg_docs/ActuatorMotors.md)
- [ActuatorServos](msg_docs/ActuatorServos.md)
- [AirspeedValidated](msg_docs/AirspeedValidated.md)
- [ArmingCheckReply](msg_docs/ArmingCheckReply.md)
- [ArmingCheckRequest](msg_docs/ArmingCheckRequest.md)
- [BatteryStatus](msg_docs/BatteryStatus.md)
- [ConfigOverrides](msg_docs/ConfigOverrides.md)
- [FixedWingLateralSetpoint](msg_docs/FixedWingLateralSetpoint.md)
- [FixedWingLongitudinalSetpoint](msg_docs/FixedWingLongitudinalSetpoint.md)
- [GotoSetpoint](msg_docs/GotoSetpoint.md)
- [HomePosition](msg_docs/HomePosition.md)
- [LateralControlConfiguration](msg_docs/LateralControlConfiguration.md)
- [LongitudinalControlConfiguration](msg_docs/LongitudinalControlConfiguration.md)
- [ManualControlSetpoint](msg_docs/ManualControlSetpoint.md)
- [ModeCompleted](msg_docs/ModeCompleted.md)
- [RegisterExtComponentReply](msg_docs/RegisterExtComponentReply.md)
@@ -531,8 +525,10 @@
- [ActuatorTest](msg_docs/ActuatorTest.md)
- [AdcReport](msg_docs/AdcReport.md)
- [Airspeed](msg_docs/Airspeed.md)
- [AirspeedValidated](msg_docs/AirspeedValidated.md)
- [AirspeedWind](msg_docs/AirspeedWind.md)
- [AutotuneAttitudeControlStatus](msg_docs/AutotuneAttitudeControlStatus.md)
- [Buffer128](msg_docs/Buffer128.md)
- [ButtonEvent](msg_docs/ButtonEvent.md)
- [CameraCapture](msg_docs/CameraCapture.md)
- [CameraStatus](msg_docs/CameraStatus.md)
@@ -571,9 +567,6 @@
- [FailsafeFlags](msg_docs/FailsafeFlags.md)
- [FailureDetectorStatus](msg_docs/FailureDetectorStatus.md)
- [FigureEightStatus](msg_docs/FigureEightStatus.md)
- [FixedWingLateralGuidanceStatus](msg_docs/FixedWingLateralGuidanceStatus.md)
- [FixedWingLateralStatus](msg_docs/FixedWingLateralStatus.md)
- [FixedWingRunwayControl](msg_docs/FixedWingRunwayControl.md)
- [FlightPhaseEstimation](msg_docs/FlightPhaseEstimation.md)
- [FollowTarget](msg_docs/FollowTarget.md)
- [FollowTargetEstimator](msg_docs/FollowTargetEstimator.md)
@@ -626,6 +619,7 @@
- [NavigatorMissionItem](msg_docs/NavigatorMissionItem.md)
- [NavigatorStatus](msg_docs/NavigatorStatus.md)
- [NormalizedUnsignedSetpoint](msg_docs/NormalizedUnsignedSetpoint.md)
- [NpfgStatus](msg_docs/NpfgStatus.md)
- [ObstacleDistance](msg_docs/ObstacleDistance.md)
- [OffboardControlMode](msg_docs/OffboardControlMode.md)
- [OnboardComputerStatus](msg_docs/OnboardComputerStatus.md)
@@ -661,12 +655,13 @@
- [RcParameterMap](msg_docs/RcParameterMap.md)
- [RoverAttitudeSetpoint](msg_docs/RoverAttitudeSetpoint.md)
- [RoverAttitudeStatus](msg_docs/RoverAttitudeStatus.md)
- [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md)
- [RoverMecanumGuidanceStatus](msg_docs/RoverMecanumGuidanceStatus.md)
- [RoverMecanumSetpoint](msg_docs/RoverMecanumSetpoint.md)
- [RoverMecanumStatus](msg_docs/RoverMecanumStatus.md)
- [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md)
- [RoverRateStatus](msg_docs/RoverRateStatus.md)
- [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md)
- [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md)
- [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md)
- [RoverVelocityStatus](msg_docs/RoverVelocityStatus.md)
- [Rpm](msg_docs/Rpm.md)
- [RtlStatus](msg_docs/RtlStatus.md)
@@ -698,7 +693,6 @@
- [TelemetryStatus](msg_docs/TelemetryStatus.md)
- [TiltrotorExtraControls](msg_docs/TiltrotorExtraControls.md)
- [TimesyncStatus](msg_docs/TimesyncStatus.md)
- [TrajectorySetpoint6dof](msg_docs/TrajectorySetpoint6dof.md)
- [TransponderReport](msg_docs/TransponderReport.md)
- [TuneControl](msg_docs/TuneControl.md)
- [UavcanParameterRequest](msg_docs/UavcanParameterRequest.md)
@@ -722,18 +716,14 @@
- [WheelEncoders](msg_docs/WheelEncoders.md)
- [Wind](msg_docs/Wind.md)
- [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md)
- [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md)
- [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](mavlink/index.md)
- [MAVLink Messaging](middleware/mavlink.md)
- [Adding Messages](mavlink/adding_messages.md)
- [Streaming Messages](mavlink/streaming_messages.md)
- [Receiving Messages](mavlink/receiving_messages.md)
- [Custom MAVLink Messages](mavlink/custom_messages.md)
- [Protocols/Microservices](mavlink/protocols.md)
- [Standard Modes Protocol](mavlink/standard_modes.md)
- [Standard Modes Protocol](mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md)
- [UORB Bridged to ROS 2](middleware/dds_topics.md)
- [모듈과 명령어](modules/modules_main.md)
- [자동 튜닝](modules/modules_autotune.md)
- [명령어](modules/modules_command.md)
@@ -862,7 +852,6 @@
- [출시](releases/index.md)
- [main (alpha)](releases/main.md)
- [1.16 (release candidate)](releases/1.16.md)
- [1.15 (stable)](releases/1.15.md)
- [1.14](releases/1.14.md)
- [1.13](releases/1.13.md)
+8 -19
View File
@@ -460,7 +460,6 @@
- [Vehicles](/sim_gazebo_gz/vehicles.md)
- [Advanced Lift Drag Tool](/sim_gazebo_gz/tools_avl_automation.md)
- [Worlds](/sim_gazebo_gz/worlds.md)
- [Plugins](/sim_gazebo_gz/plugins.md)
- [Gazebo Models Repository](/sim_gazebo_gz/gazebo_models.md)
- [Multi-Vehicle Sim](/sim_gazebo_gz/multi_vehicle_simulation.md)
- [Gazebo Classic Simulation](/sim_gazebo_classic/index.md)
@@ -493,17 +492,12 @@
- [Versioned](/msg_docs/versioned_messages.md)
- [ActuatorMotors](/msg_docs/ActuatorMotors.md)
- [ActuatorServos](/msg_docs/ActuatorServos.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [ArmingCheckReply](/msg_docs/ArmingCheckReply.md)
- [ArmingCheckRequest](/msg_docs/ArmingCheckRequest.md)
- [BatteryStatus](/msg_docs/BatteryStatus.md)
- [ConfigOverrides](/msg_docs/ConfigOverrides.md)
- [FixedWingLateralSetpoint](/msg_docs/FixedWingLateralSetpoint.md)
- [FixedWingLongitudinalSetpoint](/msg_docs/FixedWingLongitudinalSetpoint.md)
- [GotoSetpoint](/msg_docs/GotoSetpoint.md)
- [HomePosition](/msg_docs/HomePosition.md)
- [LateralControlConfiguration](/msg_docs/LateralControlConfiguration.md)
- [LongitudinalControlConfiguration](/msg_docs/LongitudinalControlConfiguration.md)
- [ManualControlSetpoint](/msg_docs/ManualControlSetpoint.md)
- [ModeCompleted](/msg_docs/ModeCompleted.md)
- [RegisterExtComponentReply](/msg_docs/RegisterExtComponentReply.md)
@@ -532,8 +526,10 @@
- [ActuatorTest](/msg_docs/ActuatorTest.md)
- [AdcReport](/msg_docs/AdcReport.md)
- [Airspeed](/msg_docs/Airspeed.md)
- [AirspeedValidated](/msg_docs/AirspeedValidated.md)
- [AirspeedWind](/msg_docs/AirspeedWind.md)
- [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md)
- [Buffer128](/msg_docs/Buffer128.md)
- [ButtonEvent](/msg_docs/ButtonEvent.md)
- [CameraCapture](/msg_docs/CameraCapture.md)
- [CameraStatus](/msg_docs/CameraStatus.md)
@@ -572,9 +568,6 @@
- [FailsafeFlags](/msg_docs/FailsafeFlags.md)
- [FailureDetectorStatus](/msg_docs/FailureDetectorStatus.md)
- [FigureEightStatus](/msg_docs/FigureEightStatus.md)
- [FixedWingLateralGuidanceStatus](/msg_docs/FixedWingLateralGuidanceStatus.md)
- [FixedWingLateralStatus](/msg_docs/FixedWingLateralStatus.md)
- [FixedWingRunwayControl](/msg_docs/FixedWingRunwayControl.md)
- [FlightPhaseEstimation](/msg_docs/FlightPhaseEstimation.md)
- [FollowTarget](/msg_docs/FollowTarget.md)
- [FollowTargetEstimator](/msg_docs/FollowTargetEstimator.md)
@@ -627,6 +620,7 @@
- [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md)
- [NavigatorStatus](/msg_docs/NavigatorStatus.md)
- [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md)
- [NpfgStatus](/msg_docs/NpfgStatus.md)
- [ObstacleDistance](/msg_docs/ObstacleDistance.md)
- [OffboardControlMode](/msg_docs/OffboardControlMode.md)
- [OnboardComputerStatus](/msg_docs/OnboardComputerStatus.md)
@@ -662,12 +656,13 @@
- [RcParameterMap](/msg_docs/RcParameterMap.md)
- [RoverAttitudeSetpoint](/msg_docs/RoverAttitudeSetpoint.md)
- [RoverAttitudeStatus](/msg_docs/RoverAttitudeStatus.md)
- [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md)
- [RoverMecanumGuidanceStatus](/msg_docs/RoverMecanumGuidanceStatus.md)
- [RoverMecanumSetpoint](/msg_docs/RoverMecanumSetpoint.md)
- [RoverMecanumStatus](/msg_docs/RoverMecanumStatus.md)
- [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md)
- [RoverRateStatus](/msg_docs/RoverRateStatus.md)
- [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md)
- [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md)
- [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md)
- [RoverVelocityStatus](/msg_docs/RoverVelocityStatus.md)
- [Rpm](/msg_docs/Rpm.md)
- [RtlStatus](/msg_docs/RtlStatus.md)
@@ -699,7 +694,6 @@
- [TelemetryStatus](/msg_docs/TelemetryStatus.md)
- [TiltrotorExtraControls](/msg_docs/TiltrotorExtraControls.md)
- [TimesyncStatus](/msg_docs/TimesyncStatus.md)
- [TrajectorySetpoint6dof](/msg_docs/TrajectorySetpoint6dof.md)
- [TransponderReport](/msg_docs/TransponderReport.md)
- [TuneControl](/msg_docs/TuneControl.md)
- [UavcanParameterRequest](/msg_docs/UavcanParameterRequest.md)
@@ -723,16 +717,13 @@
- [WheelEncoders](/msg_docs/WheelEncoders.md)
- [Wind](/msg_docs/Wind.md)
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md)
- [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](/mavlink/index.md)
- [MAVLink Messaging](/middleware/mavlink.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Protocols/Microservices](/mavlink/protocols.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [모듈과 명령어](/modules/modules_main.md)
- [자동 튜닝](/modules/modules_autotune.md)
@@ -749,7 +740,6 @@
- [자기 센서](/modules/modules_driver_magnetometer.md)
- [광류 센서](/modules/modules_driver_optical_flow.md)
- [Rpm Sensor](/modules/modules_driver_rpm_sensor.md)
- [Radio Control](/modules/modules_driver_radio_control.md)
- [Transponder](/modules/modules_driver_transponder.md)
- [추정기](/modules/modules_estimator.md)
- [시뮬레이션](/modules/modules_simulation.md)
@@ -862,7 +852,6 @@
- [출시](/releases/index.md)
- [main (alpha)](/releases/main.md)
- [1.16 (release candidate)](/releases/1.16.md)
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
@@ -128,21 +128,21 @@ You add some "boilerplate" code to regularly listen for changes in the [uORB Top
- **px4_platform_common/module_params.h** to get the `DEFINE_PARAMETERS` macro:
```cpp
#include <px4_platform_common/module_params.h>
```
```cpp
#include <px4_platform_common/module_params.h>
```
- **parameter_update.h** to access the uORB `parameter_update` message:
```cpp
#include <uORB/topics/parameter_update.h>
```
```cpp
#include <uORB/topics/parameter_update.h>
```
- **Subscription.hpp** for the uORB C++ subscription API:
```cpp
#include <uORB/Subscription.hpp>
```
```cpp
#include <uORB/Subscription.hpp>
```
Derive your class from `ModuleParams`, and use `DEFINE_PARAMETERS` to specify a list of parameters and their associated parameter attributes.
매개변수의 이름은 매개변수 메타데이터 정의와 동일하여야 합니다.
@@ -194,7 +194,7 @@ void Module::parameters_update()
- `_parameter_update_sub.updated()` tells us if there is _any_ update to the `param_update` uORB message (but not what parameter is affected).
- If there has been "some" parameter updated, we copy the update into a `parameter_update_s` (`param_update`), to clear the pending update.
- Then we call `ModuleParams::updateParams()`.
This "under the hood" updates all parameter attributes listed in our `DEFINE_PARAMETERS` list.
This "under the hood" updates all parameter attributes listed in our `DEFINE_PARAMETERS` list.
The parameter attributes (`_sys_autostart` and `_att_bias_max` in this case) can then be used to represent the parameters, and will be updated whenever the parameter value changes.
@@ -267,12 +267,12 @@ YAML meta data is intended as a full replacement for the **.c** definitions.
- An example of YAML definitions being used can be found in the MAVLink parameter definitions: [/src/modules/mavlink/module.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/module.yaml).
- YAML 파일은 다음을 추가하여 cmake 빌드 시스템에 등록됩니다.
```cmake
MODULE_CONFIG
module.yaml
```
```cmake
MODULE_CONFIG
module.yaml
```
to the `px4_add_module` section of the `CMakeLists.txt` file of that module.
to the `px4_add_module` section of the `CMakeLists.txt` file of that module.
#### 다중 인스턴스(템플릿) YAML 메타 데이터
@@ -20,7 +20,7 @@ This guide walks through the process of setting up the board and connecting to P
You will temporarily need the following hardware in order to log into your Jetson and get its IP address, after which you will be able to log in via SSH:
- External display.
If your display doesn't have a mini HDMI connector you will also need a [Mini HDMI to HDMI converter](https://a.co/d/6N815N9) if your external display has HDMI input
If your display doesn't have a mini HDMI connector you will also need a [Mini HDMI to HDMI converter](https://a.co/d/6N815N9) if your external display has HDMI input
- Ethernet cable
- Mouse and keyboard (the baseboard has 4 USB ports exposed from Jetson, two of which are USB 3.0)
@@ -45,11 +45,11 @@ This information comes from the [Holybro Pixhawk-Jetson Baseboard Documentation]
- 크기
- 126 x 80 x 45mm (with Jetson Orin NX + Heatsink/Fan & FC Module)
- 126 x 80 x 22.9mm (without Jetson and FC Module)
- 126 x 80 x 45mm (with Jetson Orin NX + Heatsink/Fan & FC Module)
- 126 x 80 x 22.9mm (without Jetson and FC Module)
- 중량
- 190g (with Jetson, Heatsink, Flight Controller, M.2 SSD, M.2 Wi-Fi Module)
- 190g (with Jetson, Heatsink, Flight Controller, M.2 SSD, M.2 Wi-Fi Module)
:::
@@ -57,67 +57,67 @@ This information comes from the [Holybro Pixhawk-Jetson Baseboard Documentation]
- 2x Gigabit Ethernet Port
- Connected to both Jetson & Autopilot via Ethernet switch (RTL8367S)
- Ethernet Switch powered by the same circuit as the Pixhawk
- 8-pin JST-GH
- RJ45
- Connected to both Jetson & Autopilot via Ethernet switch (RTL8367S)
- Ethernet Switch powered by the same circuit as the Pixhawk
- 8-pin JST-GH
- RJ45
- 2x MIPI CSI Camera Inputs
- 4 Lanes each
- 22-Pin Raspberry Pi Cam FFC
- 4 Lanes each
- 22-Pin Raspberry Pi Cam FFC
- 2x USB 3.0 Host Port
- USB A
- 5A Current Limit
- USB A
- 5A Current Limit
- 2x USB 2.0 Host Port
- 5-Pin JST-GH
- 0A Current Limit
- 5-Pin JST-GH
- 0A Current Limit
- USB 2.0 for Programming/Debugging
- USB-C
- USB-C
- 2 Key M 2242/2280 for NVMe SSD
- PCIEx4
- PCIEx4
- 2 Key E 2230 for WiFi/BT
- PCIEx2
- USB
- UART
- I2S
- PCIEx2
- USB
- UART
- I2S
- Mini HDMI Out
- 4x GPIO
- 6-pin JST-GH
- 6-pin JST-GH
- CAN Port
- Connected to Autopilot's CAN2 (4 Pin JST-GH)
- Connected to Autopilot's CAN2 (4 Pin JST-GH)
- SPI Port
- 7-Pin JST-GH
- 7-Pin JST-GH
- I2C Port
- 4-Pin JST-GH
- 4-Pin JST-GH
- I2S Port
- 7-Pin JST-GH
- 7-Pin JST-GH
- 2x UART Port
- 1 for debug
- 1 connected to Autopilot's telem2
- 1 for debug
- 1 connected to Autopilot's telem2
- Fan Power Port
@@ -129,13 +129,13 @@ This information comes from the [Holybro Pixhawk-Jetson Baseboard Documentation]
- Pixhawk Autopilot Bus Interface
- 100 Pin Hirose DF40
- 50 Pin Hirose DF40
- 100 Pin Hirose DF40
- 50 Pin Hirose DF40
- Redundant Digital Power Module Inputs
- I2C Power Monitor Support
- 2x 6-Pin Molex CLIK-Mate
- I2C Power Monitor Support
- 2x 6-Pin Molex CLIK-Mate
- Power Path Selector
@@ -143,68 +143,68 @@ This information comes from the [Holybro Pixhawk-Jetson Baseboard Documentation]
- 정격 전압
- 최대 입력 전압: 6V
- USB 전원 입력: 4.75~5.25V
- 최대 입력 전압: 6V
- USB 전원 입력: 4.75~5.25V
- Full GPS Plus Safety Switch Port
- 10-Pin JST-GH
- 10-Pin JST-GH
- Secondary (GPS2) Port
- 6-Pin JST-GH
- 6-Pin JST-GH
- 2x CAN Ports
- 4-Pin JST-GH
- 4-Pin JST-GH
- 3x Telemetry Ports with Flow Control
- 2x 6-Pin JST-GH
- 1 is connected to Jetson's `UART1` Port
- 2x 6-Pin JST-GH
- 1 is connected to Jetson's `UART1` Port
- 16 PWM Outputs
- 2x 10-Pin JST-GH
- 2x 10-Pin JST-GH
- UART4 & I2C Port
- 6-Pin JST-GH
- 6-Pin JST-GH
- 2x Gigabit Ethernet Port
- Connected to both Jetson & Autopilot via Ethernet switch (RTL8367S)
- 8-Pin JST-GH
- RJ45
- Connected to both Jetson & Autopilot via Ethernet switch (RTL8367S)
- 8-Pin JST-GH
- RJ45
- AD & IO
- 8-Pin JST-GH
- 8-Pin JST-GH
- USB 2.0
- USB-C
- 4-Pin JST-GH
- USB-C
- 4-Pin JST-GH
- DSM Input
- 3-Pin JST-ZH 1.5mm Pitch
- 3-Pin JST-ZH 1.5mm Pitch
- RC In
- PPM/SBUS
- 5-Pin JST-GH
- PPM/SBUS
- 5-Pin JST-GH
- SPI Port
- External Sensor Bus (SPI5)
- 11-Pin JST-GH
- External Sensor Bus (SPI5)
- 11-Pin JST-GH
- 2x Debug Port
- 1 for FMU
- 1 for IO
- 10-Pin JST-SH
- 1 for FMU
- 1 for IO
- 10-Pin JST-SH
:::
@@ -218,7 +218,7 @@ The Jetson has separate input power circuitry from the Pixhawk autopilot:
- 8V/3A Minimum (Depends on Usage and Peripherals)
- Voltage Rating: 7-21V (3S-4S)
- Jetson Baseboard onboard BEC is rated for 7-21V (3S-4S).
Note that the external UBEC-12A can be used for applications above 4S
Note that the external UBEC-12A can be used for applications above 4S
During development using the following wired power supply is recommended:
@@ -698,7 +698,7 @@ On the following screen, confirm your selected device:
- Choose `Pre-config` for the OEM Configuration (this will skip Ubuntu first time setup screens after reboot).
- Choose your preferred username and password (and write them down).
These will be used as your login credentials to Jetpack.
These will be used as your login credentials to Jetpack.
- Choose `NVMe` as the storage device because the board has separate SSD for storage.
![SDK Manager installation storage and OEM config page](../../assets/companion_computer/holybro_pixhawk_jetson_baseboard/nvidia_sdkmanager_3.png)
@@ -922,95 +922,95 @@ These instructions approximately mirror the [PX4 Ethernet setup](../advanced_con
Next we modify the Jetson IP address to be on the same network as the Pixhawk:
1. Make sure `netplan` is installed.
You can check by running the following command:
You can check by running the following command:
```sh
netplan -h
```
```sh
netplan -h
```
If not, install it using the commands:
If not, install it using the commands:
```sh
sudo apt update
sudo apt install netplan.io
```
```sh
sudo apt update
sudo apt install netplan.io
```
2. Check `system_networkd` is running:
```sh
sudo systemctl status systemd-networkd
```
```sh
sudo systemctl status systemd-networkd
```
You should see output like below if it is active:
You should see output like below if it is active:
```sh
● systemd-networkd.service - Network Configuration
Loaded: loaded (/lib/systemd/system/systemd-networkd.service; enabled; vendor preset: enabled)
Active: active (running) since Wed 2024-09-11 23:32:44 EDT; 23min ago
TriggeredBy: ● systemd-networkd.socket
Docs: man:systemd-networkd.service(8)
Main PID: 2452 (systemd-network)
Status: "Processing requests..."
Tasks: 1 (limit: 18457)
Memory: 2.7M
CPU: 157ms
CGroup: /system.slice/systemd-networkd.service
└─2452 /lib/systemd/systemd-networkd
```sh
● systemd-networkd.service - Network Configuration
Loaded: loaded (/lib/systemd/system/systemd-networkd.service; enabled; vendor preset: enabled)
Active: active (running) since Wed 2024-09-11 23:32:44 EDT; 23min ago
TriggeredBy: ● systemd-networkd.socket
Docs: man:systemd-networkd.service(8)
Main PID: 2452 (systemd-network)
Status: "Processing requests..."
Tasks: 1 (limit: 18457)
Memory: 2.7M
CPU: 157ms
CGroup: /system.slice/systemd-networkd.service
└─2452 /lib/systemd/systemd-networkd
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: lo: Gained carrier
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Gained IPv6LL
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: eth0: Gained IPv6LL
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: Enumeration completed
Sep 11 23:32:44 ubuntu systemd[1]: Started Network Configuration.
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Connected WiFi access point: Verizon_7YLWWD (78:67:0e:ea:a6:0>
Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo>
Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost
Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo>
Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost
```
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: lo: Gained carrier
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Gained IPv6LL
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: eth0: Gained IPv6LL
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: Enumeration completed
Sep 11 23:32:44 ubuntu systemd[1]: Started Network Configuration.
Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Connected WiFi access point: Verizon_7YLWWD (78:67:0e:ea:a6:0>
Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo>
Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost
Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo>
Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost
```
If `system_networkd` is not running, it can be enabled using:
If `system_networkd` is not running, it can be enabled using:
```sh
sudo systemctl start systemd-networkd
sudo systemctl enable systemd-networkd
```
```sh
sudo systemctl start systemd-networkd
sudo systemctl enable systemd-networkd
```
3. Open the Netplan configuration file (so we can set up a static IP for the Jetson).
The Netplan configuration file is usually located in the `/etc/netplan/` directory and named something like `01-netcfg.yaml` (the name can vary).
Below we use `nano` to open the file, but you can use your preferred text editor:
The Netplan configuration file is usually located in the `/etc/netplan/` directory and named something like `01-netcfg.yaml` (the name can vary).
Below we use `nano` to open the file, but you can use your preferred text editor:
```sh
sudo nano /etc/netplan/01-netcfg.yaml
```
```sh
sudo nano /etc/netplan/01-netcfg.yaml
```
4. Modify the yaml configuration, by overwriting the contents with the following information and then saving:
```sh
network:
version: 2
renderer: networkd
ethernets:
eth0:
dhcp4: no
addresses:
- 10.41.10.1/24
routes:
- to: 0.0.0.0/0
via: 10.41.10.254
nameservers:
addresses:
- 10.41.10.254
```
```sh
network:
version: 2
renderer: networkd
ethernets:
eth0:
dhcp4: no
addresses:
- 10.41.10.1/24
routes:
- to: 0.0.0.0/0
via: 10.41.10.254
nameservers:
addresses:
- 10.41.10.254
```
This gives the Jetson a static IP address on the Ethernet interface of `10.41.10.1` .
This gives the Jetson a static IP address on the Ethernet interface of `10.41.10.1` .
5. Apply the changes using the following command:
```sh
sudo netplan apply
```
```sh
sudo netplan apply
```
The Pixhawk Ethernet address is set to `10.41.10.2` by default, which is on the same subnet.
We can test our changes above by pinging the Pixhawk from within the Jetson terminal:
@@ -1221,15 +1221,15 @@ Assuming the client is set up as defined above:
- (Serial connection) Start the agent on `/dev/ttyTHS1`:
```sh
sudo MicroXRCEAgent serial --dev /dev/ttyTHS1 -b 921600
```
```sh
sudo MicroXRCEAgent serial --dev /dev/ttyTHS1 -b 921600
```
- (Ethernet) Start the agent on UDP port `8888`:
```sh
MicroXRCEAgent udp4 -p 8888
```
```sh
MicroXRCEAgent udp4 -p 8888
```
If your agent and client are connected and no nodes are running, you should see output similar to this in the Agent terminal:
+58 -58
View File
@@ -47,7 +47,7 @@ PX4 v1.14 (and later) supports the [LightWare LiDAR SF45](../sensor/sf45_rotatin
- Attach and configure the distance sensor on a particular port (see [sensor-specific docs](../sensor/rangefinders.md)) and enable collision prevention using [CP_DIST](#CP_DIST).
- 방향을 설정하려면 드라이버를 수정하십시오.
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
This should be done by mimicking the `SENS_CM8JL65_R_0` parameter (though you might also hard-code the orientation in the sensor _module.yaml_ file to something like `sf0x start -d ${SERIAL_DEV} -R 25` - where 25 is equivalent to `ROTATION_DOWNWARD_FACING`).
- Modify the driver to set the _field of view_ in the distance sensor UORB topic (`distance_sensor_s.h_fov`).
## PX4 (Software) Setup
@@ -203,85 +203,85 @@ The Lua script works by extracting the `obstacle_distance_fused` data at each ti
2. Configure PX4 to publish obstacle distance data (so that it is available to PlotJuggler):
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4:
```sh
- topic: /fmu/out/obstacle_distance_fused
type: px4_msgs::msg::ObstacleDistance
```
```sh
- topic: /fmu/out/obstacle_distance_fused
type: px4_msgs::msg::ObstacleDistance
```
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)_.
For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in _uXRCE-DDS (PX4-ROS 2/DDS Bridge)_.
3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section.
In the **Script Editor** tab, add following scripts in the appropriate sections:
In the **Script Editor** tab, add following scripts in the appropriate sections:
- **Global code, executed once:**
- **Global code, executed once:**
```lua
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
```
```lua
obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy")
obs_dist_min = Timeseries.new("obstacle_distance_minimum")
```
- **function(tracker_time)**
- **function(tracker_time)**
```lua
obs_dist_fused_xy:clear()
```lua
obs_dist_fused_xy:clear()
i = 0
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
min_dist = 65535
i = 0
angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset")
increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment")
min_dist = 65535
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
local angle_offset_value = angle_offset:atTime(tracker_time)
local increment_value = increment:atTime(tracker_time)
-- Cache increment and angle_offset values at tracker_time to avoid repeated calls
local angle_offset_value = angle_offset:atTime(tracker_time)
local increment_value = increment:atTime(tracker_time)
if increment_value == nil or increment_value <= 0 then
print("Invalid increment value: " .. tostring(increment_value))
return
end
if increment_value == nil or increment_value <= 0 then
print("Invalid increment value: " .. tostring(increment_value))
return
end
local max_steps = math.floor(360 / increment_value)
local max_steps = math.floor(360 / increment_value)
while i < max_steps do
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
local distance = TimeseriesView.find(str)
if distance == nil then
print("No distance data for: " .. str)
break
end
while i < max_steps do
local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i)
local distance = TimeseriesView.find(str)
if distance == nil then
print("No distance data for: " .. str)
break
end
local dist = distance:atTime(tracker_time)
if dist ~= nil and dist < 65535 then
-- Calculate angle and Cartesian coordinates
local angle = angle_offset_value + i * increment_value
local y = dist * math.cos(math.rad(angle))
local x = dist * math.sin(math.rad(angle))
local dist = distance:atTime(tracker_time)
if dist ~= nil and dist < 65535 then
-- Calculate angle and Cartesian coordinates
local angle = angle_offset_value + i * increment_value
local y = dist * math.cos(math.rad(angle))
local x = dist * math.sin(math.rad(angle))
obs_dist_fused_xy:push_back(x, y)
obs_dist_fused_xy:push_back(x, y)
-- Update minimum distance
if dist < min_dist then
min_dist = dist
end
end
-- Update minimum distance
if dist < min_dist then
min_dist = dist
end
end
i = i + 1
end
i = i + 1
end
-- Push minimum distance once after the loop
if min_dist < 65535 then
obs_dist_min:push_back(tracker_time, min_dist)
else
print("No valid minimum distance found")
end
```
-- Push minimum distance once after the loop
if min_dist < 65535 then
obs_dist_min:push_back(tracker_time, min_dist)
else
print("No valid minimum distance found")
end
```
4. Enter a name for the script on the top right, and press **Save**.
Once saved, the script should appear in the _Active Scripts_ section.
Once saved, the script should appear in the _Active Scripts_ section.
5. Start streaming the data using the approach described in [Plotting uORB Topic Data in Real Time using PlotJuggler](../debug/plotting_realtime_uorb_data.md).
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left.
Note that you have to press **Save** again to re-enable the scripts after loading a new log file or otherwise clearing data.
+43 -43
View File
@@ -71,42 +71,42 @@ Explanations and requirements:
- `/* EVENT`: This tag indicates that a comment defines metadata for the following event.
- **event_name**: the event name (`events::ID(event_name)`).
- must be unique within the whole source code of PX4.
As a general convention, prefix it with the module name, or the source file for larger modules.
- must be a valid variable name, i.e. must not contain spaces, colons, etc.
- from that name, a 24 bit event ID is derived using a hash function.
This means as long as the event name stays the same, so will the ID.
- must be unique within the whole source code of PX4.
As a general convention, prefix it with the module name, or the source file for larger modules.
- must be a valid variable name, i.e. must not contain spaces, colons, etc.
- from that name, a 24 bit event ID is derived using a hash function.
This means as long as the event name stays the same, so will the ID.
- **Log Level**:
- valid log levels are the same as used in the MAVLink [MAV_SEVERITY](https://mavlink.io/en/messages/common.html#MAV_SEVERITY) enum.
In order of descending importance these are:
- valid log levels are the same as used in the MAVLink [MAV_SEVERITY](https://mavlink.io/en/messages/common.html#MAV_SEVERITY) enum.
In order of descending importance these are:
```plain
Emergency,
Alert,
Critical,
Error,
Warning,
Notice,
Info,
Debug,
Disabled,
```
```plain
Emergency,
Alert,
Critical,
Error,
Warning,
Notice,
Info,
Debug,
Disabled,
```
- Above we specify a separate external and internal log level, which are the levels displayed to GCS users and in the log file, respectively: `{events::Log::Error, events::LogInternal::Info}`.
For the majority of cases you can pass a single log level, and this will be used for both exernal and internal cases.
There are cases it makes sense to have two different log levels.
For example an RTL failsafe action: the user should see it as Warning/Error, whereas in the log, it is an expected system response, so it can be set to `Info`.
- Above we specify a separate external and internal log level, which are the levels displayed to GCS users and in the log file, respectively: `{events::Log::Error, events::LogInternal::Info}`.
For the majority of cases you can pass a single log level, and this will be used for both exernal and internal cases.
There are cases it makes sense to have two different log levels.
For example an RTL failsafe action: the user should see it as Warning/Error, whereas in the log, it is an expected system response, so it can be set to `Info`.
- **Event Message**:
- Single-line, short message of the event.
It may contain template placeholders for arguments (e.g. `{1}`). For more information see below.
- Single-line, short message of the event.
It may contain template placeholders for arguments (e.g. `{1}`). For more information see below.
- **Event Description**:
- Detailed, optional event description.
- Can be multiple lines/paragraphs.
- It may contain template placeholders for arguments (e.g. `{2}`) and supported tags (see below)
- Detailed, optional event description.
- Can be multiple lines/paragraphs.
- It may contain template placeholders for arguments (e.g. `{2}`) and supported tags (see below)
#### Arguments and Enums
@@ -125,35 +125,35 @@ Text format for event message description:
- characters can be escaped with \\
These have to be escaped: '\\\\', '\\<', '\\{'.
These have to be escaped: '\\\\', '\\<', '\\{'.
- supported tags:
- Profiles: `<profile name="[!]NAME">CONTENT</profile>`
- Profiles: `<profile name="[!]NAME">CONTENT</profile>`
`CONTENT` will only be shown if the name matches the configured profile.
This can be used for example to hide developer information from end-users.
`CONTENT` will only be shown if the name matches the configured profile.
This can be used for example to hide developer information from end-users.
- URLs: `<a [href="URL"]>CONTENT</a>`.
If `href` is not set, use `CONTENT` as `URL` (i.e.`<a>https://docs.px4.io</a>` is interpreted as `<a href="https://docs.px4.io">https://docs.px4.io</a>`)
- URLs: `<a [href="URL"]>CONTENT</a>`.
If `href` is not set, use `CONTENT` as `URL` (i.e.`<a>https://docs.px4.io</a>` is interpreted as `<a href="https://docs.px4.io">https://docs.px4.io</a>`)
- Parameters: `<param>PARAM_NAME</param>`
- Parameters: `<param>PARAM_NAME</param>`
- no nested tags of the same type are allowed
- no nested tags of the same type are allowed
- arguments: template placeholders that follow python syntax, with 1-based indexing (instead of 0)
- general form: `{ARG_IDX[:.NUM_DECIMAL_DIGITS][UNIT]}`
- general form: `{ARG_IDX[:.NUM_DECIMAL_DIGITS][UNIT]}`
UNIT:
UNIT:
- m: horizontal distance in meters
- m_v: vertical distance in meters
- m^2: area in m^2
- m/s: speed in m/s
- C: temperature in degrees celsius
- m: horizontal distance in meters
- m_v: vertical distance in meters
- m^2: area in m^2
- m/s: speed in m/s
- C: temperature in degrees celsius
- `NUM_DECIMAL_DIGITS` only makes sense for real number arguments.
- `NUM_DECIMAL_DIGITS` only makes sense for real number arguments.
## 로깅
+1 -18
View File
@@ -187,24 +187,7 @@ Due to the inherent danger of this, this function is disabled using [CBRK_FLIGHT
## Position (GNSS) Loss Failsafe
The _Position Loss Failsafe_ is triggered if the quality of the PX4 position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate.
The sections below cover first the trigger and then the failsafe action taken by the controller.
### Position Loss Failsafe Trigger
There are basically two mechanisms in PX4 to trigger position failsafes:
- A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position.
- The estimated horizontal position accuracy exceeds a certain threshold. This check is only done on hovering systems (rotary wing vehicles or VTOLs in hover phase).
The relevant parameters shown below.
| 매개변수 | 설명 |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| <a id="EKF2_NOAID_TOUT"></a>[EKF2_NOAID_TOUT](../advanced_config/parameter_reference.md#EKF2_NOAID_TOUT) | Maximum inertial dead-reckoning time, so the time after the last data sample was received of any sensor that constrains the velocity drift [microseconds]. |
| <a id="COM_POS_FS_EPH"></a>[COM_POS_FS_EPH](../advanced_config/parameter_reference.md#COM_POS_FS_EPH) | Horizontal position error threshold for hovering vehicles (Multicopters and VTOLs in hover). Fixed-wing vehicles have this value set to infinity. |
### Position Loss Failsafe Action
The _Position Loss Failsafe_ is triggered if the quality of the PX4 global position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate.
The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information):
+14 -14
View File
@@ -38,9 +38,9 @@ A frame configuration can define everything about a vehicle, from it's geometry
When you're bringing up a new vehicle though, the frame will usually contain a fairly minimal configuration:
- Frames named with "Generic" define the vehicle type, number of rotors, and "placeholder" rotor positions.
After selecting the airframe you define the actual geometry and then configure outputs.
After selecting the airframe you define the actual geometry and then configure outputs.
- Frames named with model/brand will define the vehicle type, number of rotors, actual rotor positions, and motor directions.
After selecting the airframe you usually still have to configure outputs.
After selecting the airframe you usually still have to configure outputs.
:::
@@ -52,7 +52,7 @@ This ensures that all ESC provide exactly the same output for a given input (ide
The final step is [Motor Configuration](../config/actuators.md#motor-configuration):
- [Reverse any motors](../config/actuators.md#reversing-motors) that don't match the spin direction configured in the Geometry.
For DShot ESC you can do this through the Acuator Testing UI.
For DShot ESC you can do this through the Acuator Testing UI.
- PWM, OneShot, and CAN ESC, set the motor input limits for disarmed, low and high speed (not needed for DShot ESC)
Relevant topics:
@@ -123,14 +123,14 @@ Tuning is the final step, carried out only after most other setup and configurat
- [Autotune](../config/autotune_mc.md) — Automates tuning PX4 rate and attitude controllers (recommended).
::: info
Automatic tuning works on frames that have reasonable authority and dynamics around all the body axes.
It has primarily been tested on racing quads and X500, and is expected to be less effective on tricopters with a tiltable rotor.
::: info
Automatic tuning works on frames that have reasonable authority and dynamics around all the body axes.
It has primarily been tested on racing quads and X500, and is expected to be less effective on tricopters with a tiltable rotor.
Manual tuning using these guides are only needed if there is a problem with autotune:
Manual tuning using these guides are only needed if there is a problem with autotune:
- [MC PID Tuning (Manual/Basic)](../config_mc/pid_tuning_guide_multicopter_basic.md) — Manual tuning basic how to.
- [MC PID Tuning Guide (Manual/Detailed)](../config_mc/pid_tuning_guide_multicopter.md) — Manual tuning with detailed explanation.
- [MC PID Tuning (Manual/Basic)](../config_mc/pid_tuning_guide_multicopter_basic.md) — Manual tuning basic how to.
- [MC PID Tuning Guide (Manual/Detailed)](../config_mc/pid_tuning_guide_multicopter.md) — Manual tuning with detailed explanation.
:::
@@ -138,7 +138,7 @@ Tuning is the final step, carried out only after most other setup and configurat
- [MC Filter/Control Latency Tuning](../config_mc/filter_tuning.md) — Trade off control latency and noise filtering.
- [MC Setpoint Tuning (Trajectory Generator)](../config_mc/mc_trajectory_tuning.md)
- [MC Jerk-limited Type Trajectory](../config_mc/mc_jerk_limited_type_trajectory.md)
- [MC Jerk-limited Type Trajectory](../config_mc/mc_jerk_limited_type_trajectory.md)
- [Multicopter Racer Setup](../config_mc/racer_setup.md)
@@ -167,7 +167,7 @@ Yes but it must be physically feasible. E.g. if you make a quadrotor where all m
- [Flight Controller Peripherals](../peripherals/index.md) - Setup specific sensors, optional sensors, actuators, and so on.
- [Advanced Configuration](../advanced_config/index.md) - Factory/OEM calibration, configuring advanced features, less-common configuration.
- Vehicle-Centric Config/Tuning:
- **Multicopter Config/Tuning**
- [Helicopter Config/Tuning](../config_heli/index.md)
- [Fixed Wing Config/Tuning](../config_fw/index.md)
- [VTOL Config/Tuning](../config_vtol/index.md)
- **Multicopter Config/Tuning**
- [Helicopter Config/Tuning](../config_heli/index.md)
- [Fixed Wing Config/Tuning](../config_fw/index.md)
- [VTOL Config/Tuning](../config_vtol/index.md)
+4 -12
View File
@@ -182,19 +182,11 @@ Within the repository you created above:
5. Open previewed pages in your local editor:
First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library.
For example, you can enable VSCode as your default editor by entering:
For example, on Windows command line you can enable VSCode as your default editor by entering:
- Windows:
```sh
set EDITOR=code
```
- Linux:
```sh
export EDITOR=code
```
```sh
set EDITOR=code
```
The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link).
+3 -3
View File
@@ -96,13 +96,13 @@ Exporting the messages allows ROS 2 and the uXRCE-DDS agent to be independent of
While `px4_msgs` has messages for all uORB topics in PX4, not all messages in `px4_msgs` are available to ROS 2/PlotJuggler by default.
The set that are available must be built into the client running on PX4.
These are defined in [dds_topics.yaml](../middleware/dds_topics.md).
These are defined in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The instructions below explain the changes needed to monitor topics that are not available by default.
### Missing Topics
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](../middleware/dds_topics.md) ([source](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) to include the topic and rebuild PX4.
If a normal uORB topic is not available in PlotJuggler you will need to modify the [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) to include the topic and rebuild PX4.
If working with real hardware you will need to build and [install](../config/firmware.md#installing-px4-main-beta-or-custom-firmware) custom firmware after changing the YAML file.
@@ -122,7 +122,7 @@ cd ~/ros2_ws/ && colcon build
### Custom Topics
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](../middleware/dds_topics.md), and export the new message into your ROS 2 workspace.
After defining the topic, follow the instructions above to add the topic to [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), and export the new message into your ROS 2 workspace.
## See also
+2 -1
View File
@@ -128,7 +128,8 @@ In EKF2 mode, the replay will automatically create the ORB publisher rules descr
To perform an EKF2 replay:
- Record the original log with `SDLOG_MODE` set to `1` to log from boot.
- Record the original log.
Optionally set `SDLOG_MODE` to `1` to log from boot.
- In addition to the `replay` environment variable, set `replay_mode` to `ekf2`:
+1 -1
View File
@@ -12,7 +12,7 @@ To use it you will need to build firmware with this feature enabled and then upl
:::
:::tip
Log encryption was has been improved in PX4 v1.16 to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key).
Log encryption was has been improved in PX4 main (v1.16+) to generate a single encrypted log file that contains both encrypted log data, and an encrypted symmetric key that you can use to decrypt it (provided you can decrypt the symmetric key).
In earlier versions the encrypted symmetric key was stored in a separate file.
For more information see the [Log Encryption (PX4 v1.15)](https://docs.px4.io/v1.15/en/dev_log/log_encryption.html).
+5 -5
View File
@@ -1,6 +1,4 @@
# Holybro Kakute H743-Wing
<Badge type="tip" text="PX4 v1.16" />
# Holybro Kakute H7 V2
:::warning
PX4 does not manufacture this (or any) autopilot.
@@ -33,7 +31,9 @@ The board can be bought from one of the following shops (for example):
| Buz-, Buz+ | Piezo buzzer | |
| M1 to M14 | Motor signal outputs | |
## PX4 Bootloader Update {#bootloader}
<a id="bootloader"></a>
## 부트로더 업데이트
The board comes pre-installed with [Betaflight](https://github.com/betaflight/betaflight/wiki).
Before the PX4 firmware can be installed, the _PX4 bootloader_ must be flashed.
@@ -50,7 +50,7 @@ make holybro_kakuteh7-wing_default
## 펌웨어 설치
:::info
KakuteH7-wing is supported in PX4 v1.16 or newer.
KakuteH7-wing is supported with PX4 master & PX4 v1.16 or newer..
Prior to that release you will need to manually build and install the firmware.
:::
+5 -6
View File
@@ -41,12 +41,11 @@ The vehicle will flare if configured to do so (see [Flaring](../flight_modes_fw/
Land mode behaviour can be configured using the parameters below.
| 매개변수 | 설명 |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="NAV_LOITER_RAD"></a>[NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. |
| <a id="FW_LND_ANG"></a>[FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. |
| <a id="FW_LND_AIRSPD"></a>[FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. |
| <a id="FW_AIRSPD_FLP_SC"></a>[FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. |
| 매개변수 | 설명 |
| ----------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------- |
| <a id="NAV_LOITER_RAD"></a>[NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. |
| <a id="FW_LND_ANG"></a>[FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. |
| <a id="FW_LND_AIRSPD"></a>[FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. |
## See Also
+21 -21
View File
@@ -43,14 +43,13 @@ Reaching the clearance altitude causes the vehicle to enter [Hold mode](../fligh
Parameters that affect both catapult/hand-launch and runway takeoffs:
| 매개변수 | 설명 |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="MIS_TAKEOFF_ALT"></a>[MIS_TAKEOFF_ALT](../advanced_config/parameter_reference.md#MIS_TAKEOFF_ALT) | Minimum altitude setpoint above Home that the vehicle will climb to during takeoff. |
| <a id="FW_TKO_AIRSPD"></a>[FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Takeoff airspeed (is set to [FW_AIRSPD_MIN](../advanced_config/parameter_reference.md#FW_AIRSPD_MIN) if not defined by operator) |
| <a id="FW_TKO_PITCH_MIN"></a>[FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | This is the minimum pitch angle setpoint during the climbout phase |
| <a id="FW_T_CLMB_MAX"></a>[FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Maximum climb rate. |
| <a id="FW_FLAPS_TO_SCL"></a>[FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Flaps setpoint during takeoff |
| <a id="FW_AIRSPD_FLP_SC"></a>[FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_TKO_AIRSPD is below FW_AIRSPD_MIN. |
| 매개변수 | 설명 |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="MIS_TAKEOFF_ALT"></a>[MIS_TAKEOFF_ALT](../advanced_config/parameter_reference.md#MIS_TAKEOFF_ALT) | Minimum altitude setpoint above Home that the vehicle will climb to during takeoff. |
| <a id="FW_TKO_AIRSPD"></a>[FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Takeoff airspeed (is set to [FW_AIRSPD_MIN](../advanced_config/parameter_reference.md#FW_AIRSPD_MIN) if not defined by operator) |
| <a id="FW_TKO_PITCH_MIN"></a>[FW_TKO_PITCH_MIN](../advanced_config/parameter_reference.md#FW_TKO_PITCH_MIN) | This is the minimum pitch angle setpoint during the climbout phase |
| <a id="FW_T_CLMB_MAX"></a>[FW_T_CLMB_MAX](../advanced_config/parameter_reference.md#FW_T_CLMB_MAX) | Maximum climb rate. |
| <a id="FW_FLAPS_TO_SCL"></a>[FW_FLAPS_TO_SCL](../advanced_config/parameter_reference.md#FW_FLAPS_TO_SCL) | Flaps setpoint during takeoff |
:::info
The vehicle always respects normal FW max/min throttle settings during takeoff ([FW_THR_MIN](../advanced_config/parameter_reference.md#FW_THR_MIN), [FW_THR_MAX](../advanced_config/parameter_reference.md#FW_THR_MAX)).
@@ -102,25 +101,26 @@ The _runway takeoff mode_ has the following phases:
:::info
For a smooth takeoff, the runway wheel controller possibly needs to be tuned.
It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)).
It consists of a rate controller (P-I-FF-controller with the parameters [FW_WR_P](../advanced_config/parameter_reference.md#FW_WR_P), [FW_WR_I](../advanced_config/parameter_reference.md#FW_WR_I), [FW_WR_FF](../advanced_config/parameter_reference.md#FW_WR_FF)) and an outer loop that calculates heading setpoints from course errors and can be tuned via [RWTO_NPFG_PERIOD](#RWTO_NPFG_PERIOD).
:::
### Parameters (Runway Takeoff)
Runway takeoff is affected by the following parameters:
| 매개변수 | 설명 |
| -------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="RWTO_TKOFF"></a>[RWTO_TKOFF](../advanced_config/parameter_reference.md#RWTO_TKOFF) | Enable runway takeoff |
| <a id="FW_W_EN"></a>[FW_W_EN](../advanced_config/parameter_reference.md#FW_W_EN) | Enable wheel controller |
| <a id="RWTO_MAX_THR"></a>[RWTO_MAX_THR](../advanced_config/parameter_reference.md#RWTO_MAX_THR) | Max throttle during runway takeoff |
| <a id="RWTO_RAMP_TIME"></a>[RWTO_RAMP_TIME](../advanced_config/parameter_reference.md#RWTO_RAMP_TIME) | Throttle ramp up time |
| <a id="RWTO_ROT_AIRSPD"></a>[RWTO_ROT_AIRSPD](../advanced_config/parameter_reference.md#RWTO_ROT_AIRSPD) | Airspeed threshold to start rotation (pitching up). If not configured by operator is set to 0.9\*FW_TKO_AIRSPD. |
| <a id="RWTO_ROT_TIME"></a>[RWTO_ROT_TIME](../advanced_config/parameter_reference.md#RWTO_ROT_TIME) | This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation. |
| <a id="FW_TKO_AIRSPD"></a>[FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Airspeed setpoint during the takeoff climbout phase (after rotation). If not configured by operator is set to FW_AIRSPD_MIN. |
| <a id="RWTO_NUDGE"></a>[RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Enable wheel controller nudging while on the runway |
| <a id="FW_WING_SPAN"></a>[FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | The wingspan of the vehicle. Used to prevent wingstrikes. |
| <a id="FW_WING_HEIGHT"></a>[FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | The height of the wings above ground (ground clearance). Used to prevent wingstrikes. |
| 매개변수 | 설명 |
| ----------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="RWTO_TKOFF"></a>[RWTO_TKOFF](../advanced_config/parameter_reference.md#RWTO_TKOFF) | Enable runway takeoff |
| <a id="FW_W_EN"></a>[FW_W_EN](../advanced_config/parameter_reference.md#FW_W_EN) | Enable wheel controller |
| <a id="RWTO_MAX_THR"></a>[RWTO_MAX_THR](../advanced_config/parameter_reference.md#RWTO_MAX_THR) | Max throttle during runway takeoff |
| <a id="RWTO_RAMP_TIME"></a>[RWTO_RAMP_TIME](../advanced_config/parameter_reference.md#RWTO_RAMP_TIME) | Throttle ramp up time |
| <a id="RWTO_ROT_AIRSPD"></a>[RWTO_ROT_AIRSPD](../advanced_config/parameter_reference.md#RWTO_ROT_AIRSPD) | Airspeed threshold to start rotation (pitching up). If not configured by operator is set to 0.9\*FW_TKO_AIRSPD. |
| <a id="RWTO_ROT_TIME"></a>[RWTO_ROT_TIME](../advanced_config/parameter_reference.md#RWTO_ROT_TIME) | This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation. |
| <a id="FW_TKO_AIRSPD"></a>[FW_TKO_AIRSPD](../advanced_config/parameter_reference.md#FW_TKO_AIRSPD) | Airspeed setpoint during the takeoff climbout phase (after rotation). If not configured by operator is set to FW_AIRSPD_MIN. |
| <a id="RWTO_NUDGE"></a>[RWTO_NUDGE](../advanced_config/parameter_reference.md#RWTO_NUDGE) | Enable wheel controller nudging while on the runway |
| <a id="FW_WING_SPAN"></a>[FW_WING_SPAN](../advanced_config/parameter_reference.md#FW_WING_SPAN) | The wingspan of the vehicle. Used to prevent wingstrikes. |
| <a id="FW_WING_HEIGHT"></a>[FW_WING_HEIGHT](../advanced_config/parameter_reference.md#FW_WING_HEIGHT) | The height of the wings above ground (ground clearance). Used to prevent wingstrikes. |
| <a id="RWTO_NPFG_PERIOD"></a>[RWTO_NPFG_PERIOD](../advanced_config/parameter_reference.md#RWTO_NPFG_PERIOD) | L1 period while steering on runway. Increase for less aggressive response to course errors. |
## See Also
+1 -1
View File
@@ -137,7 +137,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS
#### Mission commands
The following commands can be used in missions at time of writing (PX4 v1.16):
The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`):
| QGC mission item | 통신 | 설명 |
| ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------------------------------------- |
+1 -1
View File
@@ -115,7 +115,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS
#### Mission commands
The following commands can be used in missions at time of writing (PX4 v1.16):
The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`):
| QGC mission item | 통신 | 설명 |
| ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ |
+1 -1
View File
@@ -140,7 +140,7 @@ The mission is typically created and uploaded with a Ground Control Station (GCS
#### Mission commands
The following commands can be used in missions at time of writing (PX4 v1.16):
The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`):
| QGC mission item | 통신 | 설명 |
| ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ |
@@ -26,13 +26,13 @@ ARF 키트는 PX4와 호환되는 대부분의 비행 콘트롤러를 지원합
The Holybro [X500 V2 Kit](https://holybro.com/collections/x500-kits) includes almost all the required components:
- X500V2 프레임 키트
- Body - Full Carbon Fiber Top & Bottom plate (144 x 144mm, 2mm thick)
- Arm - High strength & ultra-lightweight 16mm carbon fiber tubes
- Landing gear - 16mm & 10mm diameter carbon fiber tubes
- Platform board - With mounting holes for GPS & popular companion computer
- 이중 10mm Ø 로드 x 250mm 롱 레일 마운팅 시스템
- 2개의 배터리 스트랩이 있는 배터리 마운트
- 설치용 수공구
- Body - Full Carbon Fiber Top & Bottom plate (144 x 144mm, 2mm thick)
- Arm - High strength & ultra-lightweight 16mm carbon fiber tubes
- Landing gear - 16mm & 10mm diameter carbon fiber tubes
- Platform board - With mounting holes for GPS & popular companion computer
- 이중 10mm Ø 로드 x 250mm 롱 레일 마운팅 시스템
- 2개의 배터리 스트랩이 있는 배터리 마운트
- 설치용 수공구
- Holybro Motors - 2216 KV880 x6 (superseded - check [spare parts list](https://holybro.com/products/spare-parts-x500-v2-kit) for current version).
- Holybro BLHeli S ESC 20A x4 (superseded - check [spare parts list](https://holybro.com/products/spare-parts-x500-v2-kit) for current version).
- Propellers - 1045 x4 (superseded - check [spare parts list](https://holybro.com/products/spare-parts-x500-v2-kit) for current version).
@@ -93,92 +93,92 @@ Tools are included to do the assembly, however you may need:
Estimate time to assemble is 55 min (25 minutes for frame, 30 minutes for autopilot installation/configuration)
1. Start by assembling the payload & battery holder.
Push the rubbers into grippers (Do not use sharp items to push them in!).
Next, pass the holders through the holder bars with the battery holder bases as Figure 3.
Push the rubbers into grippers (Do not use sharp items to push them in!).
Next, pass the holders through the holder bars with the battery holder bases as Figure 3.
![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_required_stuff.png)
![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_required_stuff.png)
_Figure 2_: Payload holder components
_Figure 2_: Payload holder components
![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_assembled.png)
![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_assembled.png)
_Figure 3_: Payload holder assembled
_Figure 3_: Payload holder assembled
2. The next is to go for attaching the bottom plate to the payload holder.
You will need the parts as shown in Figure 4.
Then mount the base for power distribution board using nylon nuts as Figure 5.
Finally using 8 hex screws you can join the bottom plate to the payload holder (Figure 7)
You will need the parts as shown in Figure 4.
Then mount the base for power distribution board using nylon nuts as Figure 5.
Finally using 8 hex screws you can join the bottom plate to the payload holder (Figure 7)
![Materials to attach bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/topplate_holder_stuff.png)
![Materials to attach bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/topplate_holder_stuff.png)
_Figure 4_: Needed Materials
_Figure 4_: Needed Materials
![PDB mountbase](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/powerboard-mountbase.png)
![PDB mountbase](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/powerboard-mountbase.png)
_Figure 5_: PDB mount base
_Figure 5_: PDB mount base
![PDB attachment](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pdb_bottom_plate.png)
![PDB attachment](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pdb_bottom_plate.png)
_Figure 6_: Mounted pdb with nylon nuts
_Figure 6_: Mounted pdb with nylon nuts
![Bottom plate Final](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/bottom_plate_holder_final.png)
![Bottom plate Final](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/bottom_plate_holder_final.png)
_Figure 7_: Mounted Plate on payload holder
_Figure 7_: Mounted Plate on payload holder
3. Let's gather the stuff needed for mounting landing gear as Figure 8.
Use the hex screws to join landing gears to the bottom plate.
You also need to open three hex screws on each of the leg stands so you can push them into carbon fiber pipes.
Do not forget to tighten them back again.
Use the hex screws to join landing gears to the bottom plate.
You also need to open three hex screws on each of the leg stands so you can push them into carbon fiber pipes.
Do not forget to tighten them back again.
![Attach Landing Gear Stuff](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/landing_gear_materials.png)
![Attach Landing Gear Stuff](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/landing_gear_materials.png)
_Figure 8_: Required parts for landing gear attachment
_Figure 8_: Required parts for landing gear attachment
![Lanfing great to bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/attached_landing_gear.png)
![Lanfing great to bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/attached_landing_gear.png)
_Figure 9_: Landing gear attachment to the body
_Figure 9_: Landing gear attachment to the body
4. We will gather all the arms now to mount the top plate.
Please pay attention that the motor numbers on arms are a match with the ones mentioned on the top plate.
Fortunately, motors are mounted and ESCs have been connected in advance.
Start by passing through all the screws as you have the arms fixed in their own places (They have a guide as shown in Figure 11 to ensure they are in place) and tighten all nylon nuts a bit.
Then you can connect XT30 power connectors to the power board.
Please keep in mind that the signal wires have to be passed through the top plate such that we can connect them later to Pixhawk.
Please pay attention that the motor numbers on arms are a match with the ones mentioned on the top plate.
Fortunately, motors are mounted and ESCs have been connected in advance.
Start by passing through all the screws as you have the arms fixed in their own places (They have a guide as shown in Figure 11 to ensure they are in place) and tighten all nylon nuts a bit.
Then you can connect XT30 power connectors to the power board.
Please keep in mind that the signal wires have to be passed through the top plate such that we can connect them later to Pixhawk.
<img src="../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/needed_stuff_top_plate.png" width="700" title="Arms and top plate materials">
<img src="../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/needed_stuff_top_plate.png" width="700" title="Arms and top plate materials">
_Figure 10_: Connecting arms needed materials.
_Figure 10_: Connecting arms needed materials.
<img src="../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/guide_for_arm_mount.png" width="700" title="Guide for the arms mount">
<img src="../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/guide_for_arm_mount.png" width="700" title="Guide for the arms mount">
_Figure 11_: Guide for the arms mount
_Figure 11_: Guide for the arms mount
5. Tighten all 16 screws and nuts by using both hex wrench and nut driver.
![Top plae mounted](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/finalized_top_plate.png)
![Top plae mounted](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/finalized_top_plate.png)
_Figure 12_: Mounted top plate
_Figure 12_: Mounted top plate
6. Next you can mount your pixhawk on the top plate by using the stickers.
It is recommended to have the direction of your Pixhawk's arrow the same as the one mentioned on the top plate.
It is recommended to have the direction of your Pixhawk's arrow the same as the one mentioned on the top plate.
![Flight controller mounting stickers](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pixhawk5x_stickertapes.png)
![Flight controller mounting stickers](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pixhawk5x_stickertapes.png)
_Figure 13_: Sticker tapes on Pixhawk
_Figure 13_: Sticker tapes on Pixhawk
7. If you want to mount the GPS on the companion computer plate, you can now secure the GPS mount onto it using 4 screws and nuts.
<img src="../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/gps_mount_plate.png" width="400" title="Secure GPS mount onto companion plate">
<img src="../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/gps_mount_plate.png" width="400" title="Secure GPS mount onto companion plate">
_Figure 14_: Secure GPS mount onto companion plate
_Figure 14_: Secure GPS mount onto companion plate
8. 테이프를 사용하여 GPS를 GPS 마스트 상단에 붙이고 GPS 마스트를 장착합니다.
Make sure the arrow on the gps is pointing forward (Figure 15).
Make sure the arrow on the gps is pointing forward (Figure 15).
<img src="../../assets/airframes/multicopter/x500_holybro_pixhawk4/gps2.jpg" width="400" title="Figure 16: GPS and mast">
<img src="../../assets/airframes/multicopter/x500_holybro_pixhawk4/gps2.jpg" width="400" title="Figure 16: GPS and mast">
_Figure 15_: GPS and mast
_Figure 15_: GPS and mast
9. Finally, you can connect the Pixhawk interfaces such as telemetry radio to 'TELEM1' and motors signal cables accordingly.
@@ -204,14 +204,14 @@ First update the firmware, airframe, and actuator mappings:
- [Airframe](../config/airframe.md)
You will need to select the _Holybro X500 V2_ airframe (**Quadrotor x > Holybro 500 V2**)
You will need to select the _Holybro X500 V2_ airframe (**Quadrotor x > Holybro 500 V2**)
![QGroundControl - Select HolyBro 500 airframe](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/x500v2_airframe_qgc.png)
![QGroundControl - Select HolyBro 500 airframe](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/x500v2_airframe_qgc.png)
- [Actuators](../config/actuators.md)
- You should not need to update the vehicle geometry (as this is a preconfigured airframe).
- Assign actuator functions to outputs to match your wiring.
- Test the configuration using the sliders.
- You should not need to update the vehicle geometry (as this is a preconfigured airframe).
- Assign actuator functions to outputs to match your wiring.
- Test the configuration using the sliders.
그리고, 설치후에 필수적인 설정 작업과 보정 작업을 진행하여야 합니다.
+16 -16
View File
@@ -20,12 +20,12 @@ Key airframe features:
- Removable V tail or conventional tail options included
- Threaded inserts in the wings and fuselage top for external mounting
- Numerous mounting features
- Top antenna hole
- Top GPS cover
- Side "T" antenna mounts
- Rear electronics tray
- Front facing "action cam" cutout
- Front facing FPV camera cutout
- Top antenna hole
- Top GPS cover
- Side "T" antenna mounts
- Rear electronics tray
- Front facing "action cam" cutout
- Front facing FPV camera cutout
- Removable wings
- Low stall speed
- Gentle handling
@@ -69,10 +69,10 @@ Key build features
- [6s2p 18650 LiIon flight battery](https://www.upgradeenergytech.com/product-page/6s-22-2v-5600mah-30c-dark-lithium-liion-drone-battery) (select XT60 connector)
- [Custom designed 3D printed parts](https://github.com/PX4/PX4-user_guide/raw/main/assets/airframes/fw/reptile_dragon_2/rd2_3d_printed_parts.zip)
- ARK6X carrier mount
- Holybro Pixhawk 5x carrier mount
- FPV pod and camera mount
- Pitot static probe "plug" adapter
- ARK6X carrier mount
- Holybro Pixhawk 5x carrier mount
- FPV pod and camera mount
- Pitot static probe "plug" adapter
- [Custom designed power distribution PCB](https://github.com/PX4/PX4-user_guide/raw/main/assets/airframes/fw/reptile_dragon_2/xt30_power_distro_pcb.zip)
@@ -325,7 +325,7 @@ Access to this cable can be accomplished by simply removing the rear hatch and u
## Firmware Build
You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver_radio_control.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default.
You can't use prebuilt PX4 release (or main) firmware for this vehicle, as it depends on PX4 modules [crsf_rc](../modules/modules_driver.md#crsf-rc) and [msp_osd](../modules/modules_driver.md#msp-osd) that are not included by default.
These require some custom configuration to enable.
@@ -426,15 +426,15 @@ Prior to the first flight, a comprehensive preflight must be conducted.
I recommend checking the following items:
- Sensor calibration (QGC)
- Mag calibration
- Accelerometer calibration
- 대기속도 보정
- Level horizon calibration
- Mag calibration
- Accelerometer calibration
- 대기속도 보정
- Level horizon calibration
- Check control surface deflection
- Right stick -> Right aileron goes up, left aileron goes down
- Left stick -> Left aileron goes up, right aileron goes down
- Stick back -> elevator goes up
-Stick forward -> elevator goes down
-Stick forward -> elevator goes down
- Left rudder -> Rudder goes left
- Right rudder -> Rudder goes right
- Check Px4 inputs (in `stabilized mode`)
+1 -1
View File
@@ -1,6 +1,6 @@
# Ackermann Rovers
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" /> <Badge type="warning" text="Experimental" />
An _Ackermann rover_ controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates.
This kind of steering is used on most commercial vehicles, including cars, trucks etc.
+1 -1
View File
@@ -1,6 +1,6 @@
# Differential Rovers
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" /> <Badge type="warning" text="Experimental" />
A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate.
Forward motion is achieved by driving both wheels at the same speed in the same direction.
+1 -1
View File
@@ -1,6 +1,6 @@
# Mecanum Rovers
<Badge type="tip" text="PX4 v1.16" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" /> <Badge type="warning" text="Experimental" />
A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first.
Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place.
+3 -3
View File
@@ -98,11 +98,11 @@ The mapping between flight controller outputs and specific controls/motors depen
Assembly information is covered in several sections:
- [Basic Assembly](../assembly/index.md) contains topics shows the setup of core components for a number of popular [flight controllers](../flight_controller/index.md).
가이드가 없는 비행 컨트롤러는 일반적으로 거의 같은 방법으로 설정됩니다(거의 항상 유사한 설정 가이드가 포함됨).
가이드가 없는 비행 컨트롤러는 일반적으로 거의 같은 방법으로 설정됩니다(거의 항상 유사한 설정 가이드가 포함됨).
- [Peripherals](../peripherals/index.md) contains information about other peripherals, including [Airspeed Sensors](../sensor/airspeed.md).
- [Airframes Reference > VTOL](../airframes/airframe_reference.md#vtol) explains which flight controller outputs must be connected to different flight controls for each airframe configuration:
- 정의된 기체의 구성을 선택하십시오. 이는 비행을 위하여 사전 튜닝이 충분하기 때문입니다(미세 조정만 필요할 수 있음).
- 그렇지 않으면, 기체와 일치하는 "일반 기체"를 선택하십시오.
- 정의된 기체의 구성을 선택하십시오. 이는 비행을 위하여 사전 튜닝이 충분하기 때문입니다(미세 조정만 필요할 수 있음).
- 그렇지 않으면, 기체와 일치하는 "일반 기체"를 선택하십시오.
In addition, build logs showing how others have set up different types of vehicles are provided as sub topics.
For example see [FunCub QuadPlane](../frames_vtol/vtol_quadplane_fun_cub_vtol_pixhawk.md).
-89
View File
@@ -1,89 +0,0 @@
# MAVLink 메시징
[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem.
PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on.
This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices.
It also links instructions for how you can add PX4 support for:
- [Adding Standard Messages](../mavlink/adding_messages.md)
- [Streaming MAVLink messages](../mavlink/streaming_messages.md)
- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md)
- [Custom MAVLink Messages](../mavlink/custom_messages.md)
- [Protocols/Microservices](../mavlink/protocols.md)
:::info
We do not yet cover _command_ handling and sending, or how to implement your own microservices.
:::
## MAVLink Overview
MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links.
_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data.
They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement.
Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate.
[Microservices](../mavlink/protocols.md) are "meta protocols" built on top of MAVLink messages.
They are used to communicate information that cannot be sent in a single message.
For example, the [Command Protocol](https://mavlink.io/en/services/command.html) is a service for sending commands that may need acknowledgement and retransmission (quality of service).
Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values.
The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`.
The command is automatically resent a number of times if no acknowledgment is received.
Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4.
Others services include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html), [Parameter Protocol](https://mavlink.io/en/services/parameter.html), and [Mission Protocol](https://mavlink.io/en/services/mission.html).
For more information on what PX4 supports see [Microservices](../mavlink/protocols.md).
MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html).
The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages.
Note that most generated libraries do not create code to implement microservices.
The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them):
- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard.
The definitions move to `common.xml` if accepted following testing.
- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases.
These are supported by many flight stacks, ground stations, and MAVLink peripherals.
Flight stacks that use these definitions are more likely to interoperate.
- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard.
They are present on the vast majority of flight stacks and implemented in the same way.
- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation.
The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder.
The protocol relies on each end of the communication having a shared definition of what messages are being sent.
What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition.
<!--
The messages are sent over-the-wire in the "payload" of a [MAVLink packet](https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format).
In order to reduce the amount of information that must be sent, the packet does not include the message metadata, such as what fields are in the message and so on.
Instead, the fields are serialized in a predefined order based on data size and XML definition order, and MAVLink relies on each end of the communication having a shared definition of what messages are being sent.
The shared identity of the message is conveyed by the message id, along with a CRC ("`CRC_EXTRA`") that uniquely identifies the message based on its name and id, and the field names and types.
The receiving end of the communication will discard any packet for which the message id and the `CRC_EXTRA` do not match.
-->
## PX4 and MAVLink
PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras.
In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards.
:::info
To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`).
During development you can use definitions in `development.xml`.
You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions.
:::
PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink).
This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/).
The build toolchain generates the MAVLink 2 C header files at build time.
The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`:
- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36).
You can change this to any other definition file, but the file must include `common.xml`.
- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)).
The files are generated into the build directory: `/build/<build target>/mavlink/`.
-51
View File
@@ -1,51 +0,0 @@
# MAVLink Microservices (Protocols)
MAVLink "microservices" are a protocols that use multiple messages exchanged between components to communicate more complicated information.
For example, the [Command Protocol](https://mavlink.io/en/services/command.html) provides an efficient mechanism for packaging a command in a (particular) message and receiving acknowledgement of the command in another message.
MAVLink microservices are documented the [MAVLink Guide](https://mavlink.io/en/services/) (this is not exhaustive: not all messages are grouped into protocols and not all protocols are documented).
This section lists the services known to be supported/not supported by PX4 in this version.
## Supported Microservices
These services are known to be supported in some form:
- [Battery Protocol](https://mavlink.io/en/services/battery.html)
- [BATTERY_STATUS](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) and [BATTERY_INFO](https://mavlink.io/en/messages/common.html#BATTERY_STATUS) are streamed.
- Camera Protocols
- [Camera Protocol v2](https://mavlink.io/en/services/camera.html)
- [Camera Definition](https://mavlink.io/en/services/camera_def.html)
- [Command Protocol](https://mavlink.io/en/services/command.html)
- [Component Metadata Protocol](https://mavlink.io/en/services/component_information.html)
- [Events Interface](https://mavlink.io/en/services/events.html)
- [File Transfer Protocol (FTP)](https://mavlink.io/en/services/ftp.html)
- Gimbal Protocols
- [Gimbal Protocol v2](https://mavlink.io/en/services/gimbal_v2.html)
- Can be enabled by [Gimbal Configuration](../advanced/gimbal_control.md#mavlink-gimbal-mnt-mode-out-mavlink)
- PX4 an act as a MAVLink Gimbal for one FC-connected Gimbal
- [Heartbeat/Connection Protocol](https://mavlink.io/en/services/heartbeat.html)
- [High Latency Protocol](https://mavlink.io/en/services/high_latency.html) — PX4 streams [HIGH_LATENCY2](https://mavlink.io/en/messages/common.html#HIGH_LATENCY2)
- [Image Transmission Protocol](https://mavlink.io/en/services/image_transmission.html)
- [Landing Target Protocol](https://mavlink.io/en/services/landing_target.html)
- [Manual Control (Joystick) Protocol](https://mavlink.io/en/services/manual_control.html)
- [MAVLink Id Assignment (sysid, compid)](https://mavlink.io/en/services/mavlink_id_assignment.html)
- [Mission Protocol](https://mavlink.io/en/services/mission.html)
- [Offboard Control Protocol](https://mavlink.io/en/services/offboard_control.html)
- [Remote ID](../peripherals/remote_id.md) ([Open Drone ID Protocol](https://mavlink.io/en/services/opendroneid.html))
- [Parameter Protocol](https://mavlink.io/en/services/parameter.html)
- [Parameter Protocol Extended](https://mavlink.io/en/services/parameter_ext.html) — Allows setting string parameters. Used for setting string parameters set in camera definition files.
- [Payload Protocol](https://mavlink.io/en/services/payload.html)
- [Ping Protocol](https://mavlink.io/en/services/ping.html)
- [Standard Modes Protocol](../mavlink/standard_modes.md)
- [Terrain Protocol](https://mavlink.io/en/services/terrain.html)
- [Time Synchronization](https://mavlink.io/en/services/timesync.html)
- [Traffic Management (UTM/ADS-B)](https://mavlink.io/en/services/traffic_management.html)
- [Arm Authorization Protocol](https://mavlink.io/en/services/arm_authorization.html)
## 미지원
These services are not supported/used by PX4:
- [Illuminator Protocol](https://mavlink.io/en/services/illuminator.html)
- [Tunnel Protocol](https://mavlink.io/en/services/tunnel.html)
-277
View File
@@ -1,277 +0,0 @@
# dds_topics.yaml — PX4 Topics Exposed to ROS 2
:::info
This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
:::
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
## Publications
| Topic | 형식 | Rate Limit |
| --------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------- |
| `/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) | |
| `/fmu/out/arming_check_request` | [px4_msgs::msg::ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) | 5.0 |
| `/fmu/out/mode_completed` | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) | 50.0 |
| `/fmu/out/battery_status` | [px4_msgs::msg::BatteryStatus](../msg_docs/BatteryStatus.md) | 1.0 |
| `/fmu/out/collision_constraints` | [px4_msgs::msg::CollisionConstraints](../msg_docs/CollisionConstraints.md) | 50.0 |
| `/fmu/out/estimator_status_flags` | [px4_msgs::msg::EstimatorStatusFlags](../msg_docs/EstimatorStatusFlags.md) | 5.0 |
| `/fmu/out/failsafe_flags` | [px4_msgs::msg::FailsafeFlags](../msg_docs/FailsafeFlags.md) | 5.0 |
| `/fmu/out/manual_control_setpoint` | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) | 25.0 |
| `/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) | |
| `/fmu/out/position_setpoint_triplet` | [px4_msgs::msg::PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) | 5.0 |
| `/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) | |
| `/fmu/out/timesync_status` | [px4_msgs::msg::TimesyncStatus](../msg_docs/TimesyncStatus.md) | 10.0 |
| `/fmu/out/vehicle_land_detected` | [px4_msgs::msg::VehicleLandDetected](../msg_docs/VehicleLandDetected.md) | 5.0 |
| `/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) | |
| `/fmu/out/vehicle_control_mode` | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) | 50.0 |
| `/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) | |
| `/fmu/out/vehicle_global_position` | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) | 50.0 |
| `/fmu/out/vehicle_gps_position` | [px4_msgs::msg::SensorGps](../msg_docs/SensorGps.md) | 50.0 |
| `/fmu/out/vehicle_local_position` | [px4_msgs::msg::VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) | 50.0 |
| `/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) | |
| `/fmu/out/vehicle_status` | [px4_msgs::msg::VehicleStatus](../msg_docs/VehicleStatus.md) | 5.0 |
| `/fmu/out/airspeed_validated` | [px4_msgs::msg::AirspeedValidated](../msg_docs/AirspeedValidated.md) | 50.0 |
| `/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) | |
| `/fmu/out/home_position` | [px4_msgs::msg::HomePosition](../msg_docs/HomePosition.md) | 5.0 |
## Subscriptions
| Topic | 형식 |
| ------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| /fmu/in/register_ext_component_request | [px4_msgs::msg::RegisterExtComponentRequest](../msg_docs/RegisterExtComponentRequest.md) |
| /fmu/in/unregister_ext_component | [px4_msgs::msg::UnregisterExtComponent](../msg_docs/UnregisterExtComponent.md) |
| /fmu/in/config_overrides_request | [px4_msgs::msg::ConfigOverrides](../msg_docs/ConfigOverrides.md) |
| /fmu/in/arming_check_reply | [px4_msgs::msg::ArmingCheckReply](../msg_docs/ArmingCheckReply.md) |
| /fmu/in/message_format_request | [px4_msgs::msg::MessageFormatRequest](../msg_docs/MessageFormatRequest.md) |
| /fmu/in/mode_completed | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) |
| /fmu/in/config_control_setpoints | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) |
| /fmu/in/distance_sensor | [px4_msgs::msg::DistanceSensor](../msg_docs/DistanceSensor.md) |
| /fmu/in/manual_control_input | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) |
| /fmu/in/offboard_control_mode | [px4_msgs::msg::OffboardControlMode](../msg_docs/OffboardControlMode.md) |
| /fmu/in/onboard_computer_status | [px4_msgs::msg::OnboardComputerStatus](../msg_docs/OnboardComputerStatus.md) |
| /fmu/in/obstacle_distance | [px4_msgs::msg::ObstacleDistance](../msg_docs/ObstacleDistance.md) |
| /fmu/in/sensor_optical_flow | [px4_msgs::msg::SensorOpticalFlow](../msg_docs/SensorOpticalFlow.md) |
| /fmu/in/goto_setpoint | [px4_msgs::msg::GotoSetpoint](../msg_docs/GotoSetpoint.md) |
| /fmu/in/telemetry_status | [px4_msgs::msg::TelemetryStatus](../msg_docs/TelemetryStatus.md) |
| /fmu/in/trajectory_setpoint | [px4_msgs::msg::TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) |
| /fmu/in/vehicle_attitude_setpoint | [px4_msgs::msg::VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) |
| /fmu/in/vehicle_mocap_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
| /fmu/in/vehicle_rates_setpoint | [px4_msgs::msg::VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) |
| /fmu/in/vehicle_visual_odometry | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
| /fmu/in/vehicle_command | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md) |
| /fmu/in/vehicle_command_mode_executor | [px4_msgs::msg::VehicleCommand](../msg_docs/VehicleCommand.md) |
| /fmu/in/vehicle_thrust_setpoint | [px4_msgs::msg::VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) |
| /fmu/in/vehicle_torque_setpoint | [px4_msgs::msg::VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md) |
| /fmu/in/actuator_motors | [px4_msgs::msg::ActuatorMotors](../msg_docs/ActuatorMotors.md) |
| /fmu/in/actuator_servos | [px4_msgs::msg::ActuatorServos](../msg_docs/ActuatorServos.md) |
| /fmu/in/aux_global_position | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) |
| /fmu/in/fixed_wing_longitudinal_setpoint | [px4_msgs::msg::FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md) |
| /fmu/in/fixed_wing_lateral_setpoint | [px4_msgs::msg::FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) |
| /fmu/in/longitudinal_control_configuration | [px4_msgs::msg::LongitudinalControlConfiguration](../msg_docs/LongitudinalControlConfiguration.md) |
| /fmu/in/lateral_control_configuration | [px4_msgs::msg::LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) |
## Subscriptions Multi
None
## Not Exported
These messages are not listed in the yaml file.
They are not build into the module, and hence are neither published or subscribed.
:::details
See messages
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [EventV0](../msg_docs/EventV0.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [GimbalDeviceAttitudeStatus](../msg_docs/GimbalDeviceAttitudeStatus.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [InputRc](../msg_docs/InputRc.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [Event](../msg_docs/Event.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [Ping](../msg_docs/Ping.md)
- [LedControl](../msg_docs/LedControl.md)
- [Wind](../msg_docs/Wind.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [Gripper](../msg_docs/Gripper.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [LandingGear](../msg_docs/LandingGear.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [RoverVelocitySetpoint](../msg_docs/RoverVelocitySetpoint.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [Rpm](../msg_docs/Rpm.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [EscReport](../msg_docs/EscReport.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [TransponderReport](../msg_docs/TransponderReport.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [Mission](../msg_docs/Mission.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
:::
+87 -1
View File
@@ -1 +1,87 @@
<Redirect to="../mavlink/" />
# MAVLink 메시징
[MAVLink](https://mavlink.io/en/) is a very lightweight messaging protocol that has been designed for the drone ecosystem.
PX4 uses _MAVLink_ to communicate with ground stations and MAVLink SDKs, such as _QGroundControl_ and [MAVSDK](https://mavsdk.mavlink.io/), and as the integration mechanism for connecting to drone components outside of the flight controller: companion computers, MAVLink enabled cameras, and so on.
This topic provides a brief overview of fundamental MAVLink concepts, such as messages, commands, and microservices.
It also links instructions for how you can add PX4 support for:
- [Adding Standard Messages](../mavlink/adding_messages.md)
- [Streaming MAVLink messages](../mavlink/streaming_messages.md)
- [Handling incoming MAVLink messages (and writing to a uORB topic)](../mavlink/receiving_messages.md)
- [Custom MAVLink Messages](../mavlink/custom_messages.md)
:::info
We do not yet cover _command_ handling and sending, or how to implement your own microservices.
:::
## MAVLink Overview
MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links.
_Messages_ are simplest and most "fundamental" definition in MAVLink, consisting of a name (e.g. [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)), id, and fields containing relevant data.
They are deliberately lightweight, with a constrained size, and no semantics for resending and acknowledgement.
Stand-alone messages are commonly used for streaming telemetry or status information, and for sending commands where no acknowledgement is required - such as setpoint commands sent at high rate.
The [Command Protocol](https://mavlink.io/en/services/command.html) is a higher level protocol for sending commands that may need acknowledgement.
Specific commands are defined as values of the [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) enumeration, such as the takeoff command [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF), and include up to 7 numeric "param" values.
The protocol sends a command by packaging the parameter values in a `COMMAND_INT` or `COMMAND_LONG` message, and waits for an acknowledgement with a result in a `COMMAND_ACK`.
The command is resent automatically if no acknowledgment is received.
Note that [MAV_CMD](https://mavlink.io/en/messages/common.html#mav_commands) definitions are also used to define mission actions, and that not all definitions are supported for use in commands/missions on PX4.
[Microservices](https://mavlink.io/en/services/) are other higher level protocols built on top of MAVLink messages.
They are used to communicate information that cannot be sent in a single message, and to deliver features such as reliable communication.
The command protocol described above is one such service.
Others include the [File Transfer Protocol](https://mavlink.io/en/services/ftp.html), [Camera Protocol](https://mavlink.io/en/services/camera.html) and [Mission Protocol](https://mavlink.io/en/services/mission.html).
MAVLink messages, commands and enumerations are defined in [XML definition files](https://mavlink.io/en/guide/define_xml_element.html).
The MAVLink toolchain includes code generators that create programming-language-specific libraries from these definitions for sending and receiving messages.
Note that most generated libraries do not create code to implement microservices.
The MAVLink project standardizes a number of messages, commands, enumerations, and microservices, for exchanging data using the following definition files (note that higher level files _include_ the definitions of the files below them):
- [development.xml](https://mavlink.io/en/messages/development.html) — Definitions that are proposed to be part of the standard.
The definitions move to `common.xml` if accepted following testing.
- [common.xml](https://mavlink.io/en/messages/common.html) — A "library" of definitions meeting many common UAV use cases.
These are supported by many flight stacks, ground stations, and MAVLink peripherals.
Flight stacks that use these definitions are more likely to interoperate.
- [standard.xml](https://mavlink.io/en/messages/standard.html) — Definitions that are actually standard.
They are present on the vast majority of flight stacks and implemented in the same way.
- [minimal.xml](https://mavlink.io/en/messages/minimal.html) — Definitions required by a minimal MAVLink implementation.
The project also hosts [dialect XML definitions](https://mavlink.io/en/messages/#dialects), which contain MAVLink definitions that are specific to a flight stack or other stakeholder.
The protocol relies on each end of the communication having a shared definition of what messages are being sent.
What this means is that in order to communicate both ends of the communication must use libraries generated from the same XML definition.
<!--
The messages are sent over-the-wire in the "payload" of a [MAVLink packet](https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format).
In order to reduce the amount of information that must be sent, the packet does not include the message metadata, such as what fields are in the message and so on.
Instead, the fields are serialized in a predefined order based on data size and XML definition order, and MAVLink relies on each end of the communication having a shared definition of what messages are being sent.
The shared identity of the message is conveyed by the message id, along with a CRC ("`CRC_EXTRA`") that uniquely identifies the message based on its name and id, and the field names and types.
The receiving end of the communication will discard any packet for which the message id and the `CRC_EXTRA` do not match.
-->
## PX4 and MAVLink
PX4 releases build `common.xml` MAVLink definitions by default, for the greatest compatibility with MAVLink ground stations, libraries, and external components such as MAVLink cameras.
In the `main` branch, these are included from `development.xml` on SITL, and `common.xml` for other boards.
:::info
To be part of a PX4 release, any MAVLink definitions that you use must be in `common.xml` (or included files such as `standard.xml` and `minimal.xml`).
During development you can use definitions in `development.xml`.
You will need to work with the [MAVLink team](https://mavlink.io/en/contributing/contributing.html) to define and contribute these definitions.
:::
PX4 includes the [mavlink/mavlink](https://github.com/mavlink/mavlink) repo as a submodule under [/src/modules/mavlink](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mavlink).
This contains XML definition files in [/mavlink/messages/1.0/](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/).
The build toolchain generates the MAVLink 2 C header files at build time.
The XML file for which headers files are generated may be defined in the [PX4 kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) on a per-board basis, using the variable `CONFIG_MAVLINK_DIALECT`:
- For SITL `CONFIG_MAVLINK_DIALECT` is set to `development` in [boards/px4/sitl/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/sitl/default.px4board#L36).
You can change this to any other definition file, but the file must include `common.xml`.
- For other boards `CONFIG_MAVLINK_DIALECT` is not set by default, and PX4 builds the definitions in `common.xml` (these are build into the [mavlink module](../modules/modules_communication.md#mavlink) by default — search for `menuconfig MAVLINK_DIALECT` in [src/modules/mavlink/Kconfig](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mavlink/Kconfig#L10)).
The files are generated into the build directory: `/build/<build target>/mavlink/`.
+7 -26
View File
@@ -61,12 +61,12 @@ For example the [VelocityLimits](../msg_docs/VelocityLimits.md) message definiti
```text
# Velocity and yaw rate limits for a multicopter position slow mode only
uint64 timestamp # [us] Time since system start.
uint64 timestamp # time since system start (microseconds)
# absolute speeds, NAN means use default limit
float32 horizontal_velocity # [m/s] Horizontal velocity.
float32 vertical_velocity # [m/s] Vertical velocity.
float32 yaw_rate # [rad/s] Yaw rate.
float32 horizontal_velocity # [m/s]
float32 vertical_velocity # [m/s]
float32 yaw_rate # [rad/s]
```
By default this message definition will be compiled to a single topic with an id `velocity_limits`, a direct conversion from the CamelCase name to a snake_case version.
@@ -92,34 +92,15 @@ To nest a message, simply include the nested message type in the parent message
```text
# Global position setpoint triplet in WGS84 coordinates.
#
# This are the three next waypoints (or just the next two or one).
uint64 timestamp # [us] Time since system start.
uint64 timestamp # time since system start (microseconds)
PositionSetpoint previous
PositionSetpoint current
PositionSetpoint next
```
### uORB Buffer Length (ORB_QUEUE_LENGTH)
uORB messages have a single-message buffer by default, which may be overwritten if the message publication rate is too high.
In most cases this does not matter: either we are only interested in the latest sample of a topic, such as a sensor value or a setpoint, or losing a few samples is not a particular problem.
For relatively few cases, such as vehicle commands, it is important that we don't drop topics.
In order to reduce the chance that messages will be dropped we can use named constant `ORB_QUEUE_LENGTH` to create a buffer of the specified length.
For example, to create a four-message queue, add the following line to your message definition:
```sh
uint8 ORB_QUEUE_LENGTH = 4
```
As long as subscribers are able to read messages out of the buffer quickly enough than it isn't ever fully filled to the queue length (by publishers), they will be able to get all messages that are sent.
Messages will still be lost they are published when the queue is filled.
Note that the queue length value must be a power of 2 (so 2, 4, 8, ...).
### Message/Field Deprecation {#deprecation}
As there are external tools using uORB messages from log files, such as [Flight Review](https://github.com/PX4/flight_review), certain aspects need to be considered when updating existing messages:
@@ -135,9 +116,9 @@ As there are external tools using uORB messages from log files, such as [Flight
## Message Versioning
<Badge type="tip" text="PX4 v1.16" />
<Badge type="tip" text="main (planned for: PX4 v1.16+)" />
Optional message versioning was introduced PX4 v1.16 to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions.
Optional message versioning was introduced in the `main` branch (planned for PX4 v1.16+) to make it easier to maintain compatibility between PX4 and ROS 2 versions compiled against different message definitions.
Versioned messages are designed to remain more stable over time compared to their non-versioned counterparts, as they are intended to be used across multiple releases of PX4 and external systems, ensuring greater compatibility over longer periods.
Versioned messages include an additional field `uint32 MESSAGE_VERSION = x`, where `x` corresponds to the current version of the message.
+9 -12
View File
@@ -38,7 +38,7 @@ The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is gen
The agent has no dependency on client code.
It can be built standalone or in a ROS 2 workspace, or installed as a snap package on Ubuntu.
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [/src/modules/uxrce_dds_client/dds_topics.yaml](../middleware/dds_topics.md) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
When PX4 is built, a code generator uses the uORB message definitions in the source tree ([PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)) to compile support for the subset of uORB topics in [PX4-Autopilot/src/modules/uxrce_dds_client/dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client).
PX4 main or release builds automatically export the set of uORB messages definitions in the build to an associated branch in [PX4/px4_msgs](https://github.com/PX4/px4_msgs).
@@ -326,11 +326,13 @@ ROS_DOMAIN_ID=3 PX4_UXRCE_DDS_PORT=9999 PX4_UXRCE_DDS_NS=drone make px4_sitl gz_
## Supported uORB Messages
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](../middleware/dds_topics.md).
The set of [PX4 uORB topics](../msg_docs/index.md) that are exposed through the client are set in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml).
The topics are release specific (support is compiled into [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) at build time).
While most releases should support a very similar set of messages, to be certain you would need to check the yaml file for your particular release.
<!-- Jublish the set we use?: https://github.com/PX4/px4_msgs/issues/22 -->
Note that ROS 2/DDS needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages.
The message definitions are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs), and they are automatically synchronized by CI on the `main` and release branches.
Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics.
@@ -347,21 +349,21 @@ Therefore,
```
::: info
Technically, [dds_topics.yaml](../middleware/dds_topics.md) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages.
For more information see [DDS Topics YAML](#dds-topics-yaml) below.
:::
## Customizing the Namespace
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations):
Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (which is useful for multi vehicle operations):
- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line.
This technique can be used both in simulation and real vehicles.
- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation.
:::info
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#dds-ros-2-services).
Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) and all [service servers](#dds-ros-2-services).
Therefore, commands like:
```sh
@@ -418,7 +420,7 @@ Deadline, lifespan, and lease durations are also all set to "default".
## DDS Topics YAML
The PX4 [dds_topics.yaml](../middleware/dds_topics.md) file defines the set of PX4 uORB topics that are built into firmware and published.
The PX4 yaml file [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) defines the set of PX4 uORB topics that are built into firmware and published.
More precisely, it completely defines the relationship/pairing between PX4 uORB and ROS 2 messages.
The file is structured as follows:
@@ -428,17 +430,14 @@ publications:
- topic: /fmu/out/collision_constraints
type: px4_msgs::msg::CollisionConstraints
rate_limit: 50. # Limit max publication rate to 50 Hz
...
- topic: /fmu/out/vehicle_odometry
type: px4_msgs::msg::VehicleOdometry
# Use default publication rate limit of 100 Hz
- topic: /fmu/out/vehicle_status
type: px4_msgs::msg::VehicleStatus
rate_limit: 5.
- topic: /fmu/out/vehicle_trajectory_waypoint_desired
type: px4_msgs::msg::VehicleTrajectoryWaypoint
@@ -473,8 +472,6 @@ Each (`topic`,`type`) pairs defines:
- `/fmu/out/` for topics that are _published_ by PX4.
- `/fmu/in/` for topics that are _subscribed_ by PX4.
4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition.
5. **(Optional)**: An additional `rate_limit` field (only for publication entries), which specifies the maximum rate (Hz) at which messages will be published on this topic by PX4 to ROS 2.
If left unspecified, the maximum publication rate limit is set to 100 Hz.
`subscriptions` and `subscriptions_multi` allow us to choose the uORB topic instance that ROS 2 topics are routed to: either a shared instance that may also be getting updates from internal PX4 uORB publishers, or a separate instance that is reserved for ROS2 publications, respectively.
Without this mechanism all ROS 2 messages would be routed to the _same_ uORB topic instance (because ROS 2 does not have the concept of [multiple topic instances](../middleware/uorb.md#multi-instance)), and it would not be possible for PX4 subscribers to differentiate between streams from ROS 2 or PX4 publishers.
@@ -547,7 +544,7 @@ Take a look at the [client startup section](#starting-the-client) to learn how t
#### New file for setting which topics are published
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topics.yaml](../middleware/dds_topics.md) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
The list of topics that are published and subscribed for a particular firmware is now managed by the [dds_topic.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) configuration file, which replaces [urtps_bridge_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/release/1.13/msg/tools/urtps_bridge_topics.yaml)
See [Supported uORB Messages](#supported-uorb-messages) and [DDS Topics YAML](#dds-topics-yaml) sections for more information.

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