Compare commits
1 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| af439dc630 |
@@ -1,9 +1,22 @@
|
||||
<!--
|
||||
|
||||
Thank you for your contribution!
|
||||
|
||||
Get early feedback through
|
||||
- Dronecode Discord: https://discord.gg/dronecode
|
||||
- PX4 Discuss: http://discuss.px4.io/
|
||||
- opening a draft pr and sharing the link
|
||||
|
||||
-->
|
||||
|
||||
### Solved Problem
|
||||
When ... I found that ...
|
||||
|
||||
Fixes #{Github issue ID}
|
||||
|
||||
### Solution
|
||||
- Add ... for ...
|
||||
- Refactor ...
|
||||
|
||||
### Changelog Entry
|
||||
For release notes:
|
||||
@@ -14,10 +27,11 @@ Documentation: Need to clarify page ... / done, read docs.px4.io/...
|
||||
```
|
||||
|
||||
### Alternatives
|
||||
We could also ...
|
||||
|
||||
### Test coverage
|
||||
- Unit/integration test: ...
|
||||
- Simulation/hardware testing logs: https://review.px4.io/
|
||||
|
||||
### Context
|
||||
Related links, screenshot before/after, video
|
||||
|
||||
-->
|
||||
|
||||
@@ -11,6 +11,8 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=advanced_plane}
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
|
||||
param set-default SENS_EN_ARSPDSIM 1
|
||||
|
||||
param set-default FW_LND_ANG 8
|
||||
|
||||
param set-default FW_PR_FF 0.08
|
||||
|
||||
@@ -159,19 +159,24 @@ if [ -n "${PX4_SIM_MODEL#*gz_}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then
|
||||
fi
|
||||
|
||||
# Set up camera to follow the model if requested
|
||||
if [ -z "${PX4_GZ_NO_FOLLOW}" ]; then
|
||||
if [ -n "${PX4_GZ_FOLLOW}" ]; then
|
||||
|
||||
echo "INFO [init] Setting camera to follow ${MODEL_NAME_INSTANCE}"
|
||||
|
||||
# Set camera to follow the model
|
||||
${gz_command} service -s "/gui/follow" --reqtype gz.msgs.StringMsg \
|
||||
--reptype gz.msgs.Boolean --timeout 5000 \
|
||||
--req "data: \"${MODEL_NAME_INSTANCE}\"" > /dev/null 2>&1
|
||||
|
||||
# Set default camera offset if not specified
|
||||
follow_x=${PX4_GZ_FOLLOW_OFFSET_X:--2.0}
|
||||
follow_y=${PX4_GZ_FOLLOW_OFFSET_Y:--2.0}
|
||||
follow_z=${PX4_GZ_FOLLOW_OFFSET_Z:-2.0}
|
||||
|
||||
# Set camera offset
|
||||
${gz_command} topic -t /gui/track -m gz.msgs.CameraTrack \
|
||||
-p "track_mode: FOLLOW, follow_target: {name: '${MODEL_NAME_INSTANCE}'},\
|
||||
follow_offset: {x: ${follow_x}, y: ${follow_y}, z: ${follow_z}}, follow_pgain: 1.0, track_pgain: 1.0"
|
||||
${gz_command} service -s "/gui/follow/offset" --reqtype gz.msgs.Vector3d \
|
||||
--reptype gz.msgs.Boolean --timeout 5000 \
|
||||
--req "x: ${follow_x}, y: ${follow_y}, z: ${follow_z}" > /dev/null 2>&1
|
||||
|
||||
echo "INFO [init] Camera follow offset set to ${follow_x}, ${follow_y}, ${follow_z}"
|
||||
fi
|
||||
|
||||
@@ -231,12 +231,6 @@ then
|
||||
ads7953 start -S
|
||||
fi
|
||||
|
||||
# ADC sensor tla2528 external I2C
|
||||
if param compare -s ADC_TLA2528_EN 1
|
||||
then
|
||||
tla2528 start -X
|
||||
fi
|
||||
|
||||
# probe for optional external I2C devices
|
||||
if param compare SENS_EXT_I2C_PRB 1
|
||||
then
|
||||
|
||||
@@ -238,7 +238,6 @@ def get_actuator_output(yaml_config, output_functions, timer_config_file, verbos
|
||||
( 'disarmed', 'Disarmed', 'DIS', False ),
|
||||
( 'min', 'Minimum', 'MIN', False ),
|
||||
( 'max', 'Maximum', 'MAX', False ),
|
||||
( 'center', 'Center\n(for Servos)', 'CENT', False ),
|
||||
( 'failsafe', 'Failsafe', 'FAIL', True ),
|
||||
]
|
||||
for key, label, param_suffix, advanced in standard_params_array:
|
||||
|
||||
@@ -284,9 +284,6 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR
|
||||
'''
|
||||
minimum_description = \
|
||||
'''Minimum output value (when not disarmed).
|
||||
'''
|
||||
center_description = \
|
||||
'''Servo Center output value (when not disarmed).
|
||||
'''
|
||||
maximum_description = \
|
||||
'''Maxmimum output value (when not disarmed).
|
||||
@@ -299,7 +296,6 @@ When set to -1 (default), the value depends on the function (see {:}).
|
||||
standard_params_array = [
|
||||
( 'disarmed', 'Disarmed', 'DIS', disarmed_description ),
|
||||
( 'min', 'Minimum', 'MIN', minimum_description ),
|
||||
( 'center', 'Center', 'CENT', center_description ),
|
||||
( 'max', 'Maximum', 'MAX', maximum_description ),
|
||||
( 'failsafe', 'Failsafe', 'FAIL', failsafe_description ),
|
||||
]
|
||||
@@ -316,10 +312,6 @@ When set to -1 (default), the value depends on the function (see {:}).
|
||||
standard_params[key]['default'] = -1
|
||||
standard_params[key]['min'] = -1
|
||||
|
||||
if key == 'center':
|
||||
standard_params[key]['default'] = -1
|
||||
standard_params[key]['min'] = -1
|
||||
|
||||
param = {
|
||||
'description': {
|
||||
'short': channel_label+' ${i} '+label+' Value',
|
||||
|
||||
@@ -132,6 +132,7 @@ ENTRY(_stext)
|
||||
*/
|
||||
EXTERN(abort)
|
||||
EXTERN(_bootdelay_signature)
|
||||
EXTERN(board_get_manifest)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
|
||||
@@ -48,6 +48,7 @@ else()
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
mtd.cpp
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
@@ -30,48 +30,47 @@
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include "tla2528.h"
|
||||
|
||||
void TLA2528::print_usage()
|
||||
#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)
|
||||
{
|
||||
PRINT_MODULE_USAGE_NAME("TLA2528", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("adc");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
extern "C" int tla2528_main(int argc, char *argv[])
|
||||
{
|
||||
using ThisDriver = TLA2528;
|
||||
BusCLIArguments cli{true, false};
|
||||
|
||||
cli.default_i2c_frequency = 400000;
|
||||
cli.i2c_address = 0x10;
|
||||
const char *name = MODULE_NAME;
|
||||
const char *verb = cli.parseDefaultArguments(argc, argv);
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(name, cli, DRV_ADC_DEVTYPE_TLA2528);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
return &mft;
|
||||
}
|
||||
@@ -67,6 +67,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -3,13 +3,19 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set - default SENS_EN_INA238 0
|
||||
param set - default SENS_EN_INA228 0
|
||||
param set - default SENS_EN_INA226 0
|
||||
|
||||
# Mavlink ethernet (CFG 1000)
|
||||
param set-default MAV_2_CONFIG 1000
|
||||
param set-default MAV_2_BROADCAST 1
|
||||
param set-default MAV_2_MODE 0
|
||||
param set-default MAV_2_RADIO_CTL 0
|
||||
param set-default MAV_2_RATE 100000
|
||||
param set-default MAV_2_REMOTE_PRT 14550
|
||||
param set-default MAV_2_UDP_PRT 14550
|
||||
param set - default MAV_2_CONFIG 1000
|
||||
param set - default MAV_2_BROADCAST 1
|
||||
param set - default MAV_2_MODE 0
|
||||
param set - default MAV_2_RADIO_CTL 0
|
||||
param set - default MAV_2_RATE 100000
|
||||
param set - default MAV_2_REMOTE_PRT 14550
|
||||
param set - default MAV_2_UDP_PRT 14550
|
||||
|
||||
safety_button start
|
||||
|
||||
@@ -72,6 +72,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -14,7 +14,10 @@ param set-default MAV_2_RATE 100000
|
||||
param set-default MAV_2_REMOTE_PRT 14550
|
||||
param set-default MAV_2_UDP_PRT 14550
|
||||
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 1
|
||||
|
||||
param set-default SENS_EN_THERMAL 1
|
||||
param set-default SENS_IMU_MODE 1
|
||||
param set-default SENS_IMU_TEMP 10.0
|
||||
|
||||
@@ -50,6 +50,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -41,6 +41,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -58,6 +58,7 @@ CONFIG_LOGGER_STACK_SIZE=4100
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
@@ -77,7 +78,9 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_GPIO=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
@@ -89,6 +92,7 @@ CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||
CONFIG_SYSTEMCMDS_SD_STRESS=y
|
||||
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
|
||||
@@ -3,6 +3,12 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA226 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA238 0
|
||||
|
||||
# Set the backend of the dataman to SRAM
|
||||
param set-default SYS_DM_BACKEND 1
|
||||
# Set TELEM1 as default mavlink connection
|
||||
|
||||
@@ -3,6 +3,12 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
# Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client
|
||||
param set-default UXRCE_DDS_PTCFG 2
|
||||
param set-default UXRCE_DDS_AG_IP 170461697
|
||||
|
||||
@@ -14,7 +14,6 @@ CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_LINUX_PWM_OUT=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
@@ -31,8 +30,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_LATERAL_LONGITUDINAL_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
|
||||
|
||||
@@ -61,6 +61,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -3,6 +3,13 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
|
||||
# Mavlink ethernet (CFG 1000)
|
||||
param set-default MAV_2_CONFIG 1000
|
||||
param set-default MAV_2_BROADCAST 1
|
||||
|
||||
@@ -15,6 +15,10 @@ param set-default MAV_2_UDP_PRT 14550
|
||||
param set-default BAT1_V_DIV 18
|
||||
param set-default BAT1_A_PER_V 24
|
||||
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
param set-default USB_MAV_MODE 5
|
||||
|
||||
param set-default UAVCAN_SUB_GPS 1
|
||||
|
||||
@@ -12,6 +12,10 @@ param set-default MAV_2_RATE 100000
|
||||
param set-default MAV_2_REMOTE_PRT 14550
|
||||
param set-default MAV_2_UDP_PRT 14550
|
||||
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
param set-default RC_CRSF_PRT_CFG 300
|
||||
param set-default RC_CRSF_TEL_EN 1
|
||||
param set-default RC_SBUS_PRT_CFG 0
|
||||
|
||||
@@ -12,6 +12,10 @@ param set-default MAV_2_RATE 100000
|
||||
param set-default MAV_2_REMOTE_PRT 14550
|
||||
param set-default MAV_2_UDP_PRT 14550
|
||||
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
param set-default BAT1_V_DIV 18.000000000
|
||||
param set-default BAT1_A_PER_V 38.462030303
|
||||
|
||||
|
||||
@@ -74,6 +74,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -3,6 +3,10 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
if ver hwbasecmp 008 009 00a 010 011
|
||||
then
|
||||
# Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client
|
||||
|
||||
@@ -71,6 +71,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -3,6 +3,12 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
# Mavlink ethernet (CFG 1000)
|
||||
param set-default MAV_2_CONFIG 1000
|
||||
param set-default MAV_2_BROADCAST 1
|
||||
|
||||
@@ -1 +0,0 @@
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
@@ -1,5 +1,4 @@
|
||||
# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set
|
||||
CONFIG_DRIVERS_UAVCAN=n
|
||||
CONFIG_MODULES_UXRCE_DDS_CLIENT=n
|
||||
CONFIG_BOARD_CONSTRAINED_FLASH=y
|
||||
CONFIG_MODULES_ZENOH=y
|
||||
|
||||
@@ -12,6 +12,12 @@ param set-default MAV_2_RATE 100000
|
||||
param set-default MAV_2_REMOTE_PRT 14550
|
||||
param set-default MAV_2_UDP_PRT 14550
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
safety_button start
|
||||
|
||||
if param greater -s UAVCAN_ENABLE 0
|
||||
|
||||
@@ -35,6 +35,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -1 +0,0 @@
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
@@ -34,6 +34,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -63,6 +63,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -3,6 +3,12 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
# Mavlink ethernet (CFG 1000)
|
||||
param set-default MAV_2_CONFIG 1000
|
||||
param set-default MAV_2_BROADCAST 1
|
||||
|
||||
@@ -61,6 +61,7 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
|
||||
@@ -3,6 +3,12 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
if ver hwbasecmp 009 010 011
|
||||
then
|
||||
# Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client
|
||||
|
||||
@@ -325,6 +325,7 @@
|
||||
1 1 COM_PREARM_MODE 0 6
|
||||
1 1 COM_QC_ACT 0 6
|
||||
1 1 COM_RCL_EXCEPT 0 6
|
||||
1 1 COM_RC_ARM_HYST 1000 6
|
||||
1 1 COM_RC_IN_MODE 3 6
|
||||
1 1 COM_RC_LOSS_T 0.500000000000000000 9
|
||||
1 1 COM_RC_OVERRIDE 1 6
|
||||
|
||||
|
Before Width: | Height: | Size: 112 KiB |
|
Before Width: | Height: | Size: 18 KiB |
|
Before Width: | Height: | Size: 29 KiB |
|
Before Width: | Height: | Size: 89 KiB After Width: | Height: | Size: 240 KiB |
|
Before Width: | Height: | Size: 26 KiB |
|
Before Width: | Height: | Size: 55 KiB |
|
Before Width: | Height: | Size: 56 KiB |
|
Before Width: | Height: | Size: 7.0 KiB |
|
Before Width: | Height: | Size: 36 KiB |
|
Before Width: | Height: | Size: 8.5 KiB |
|
Before Width: | Height: | Size: 47 KiB |
|
Before Width: | Height: | Size: 10 KiB |
|
Before Width: | Height: | Size: 36 KiB |
@@ -56,14 +56,11 @@
|
||||
- [DJI F450 (CUAV v5 nano)](frames_multicopter/dji_f450_cuav_5nano.md)
|
||||
|
||||
- [Planes (Fixed-Wing)](frames_plane/index.md)
|
||||
- [Features](features_fw/index.md)
|
||||
- [Gain compression](features_fw/gain_compression.md)
|
||||
- [Assembly](assembly/assembly_fw.md)
|
||||
- [Config/Tuning](config_fw/index.md)
|
||||
- [Auto-tune](config/autotune_fw.md)
|
||||
- [Rate/Attitude Controller Tuning Guide](config_fw/pid_tuning_guide_fixedwing.md)
|
||||
- [Altitude/Position Controller Tuning Guide](config_fw/position_tuning_guide_fixedwing.md)
|
||||
- [Airspeed Scale Estimate Handling](config_fw/airspeed_scale_handling.md)
|
||||
- [Weight & Altitude Tuning](config_fw/weight_and_altitude_tuning.md)
|
||||
- [Trimming Guide](config_fw/trimming_guide_fixedwing.md)
|
||||
- [Flying (Basics)](flying/basic_flying_fw.md)
|
||||
@@ -244,22 +241,18 @@
|
||||
- [TFSlot Airspeed Sensor](sensor/airspeed_tfslot.md)
|
||||
- [Barometers](sensor/barometer.md)
|
||||
- [Distance Sensors \(Rangefinders\)](sensor/rangefinders.md)
|
||||
- [Ainstein US-D1 Standard Radar Altimeter](sensor/ulanding_radar.md)
|
||||
- [ARK DIST SR (CAN/UART)](dronecan/ark_dist.md)
|
||||
- [ARK DIST MR (CAN/UART)](dronecan/ark_dist_mr.md)
|
||||
- [Benewake TFmini Lidar](sensor/tfmini.md)
|
||||
- [LeddarOne Lidar](sensor/leddar_one.md)
|
||||
- [Lidar-Lite](sensor/lidar_lite.md)
|
||||
- [Lightware Lidars (SF/LW)](sensor/sfxx_lidar.md)
|
||||
- [Lightware SF45 Rotary Lidar](sensor/sf45_rotating_lidar.md)
|
||||
- [Ainstein US-D1 Standard Radar Altimeter](sensor/ulanding_radar.md)
|
||||
- [LeddarOne Lidar](sensor/leddar_one.md)
|
||||
- [Benewake TFmini Lidar](sensor/tfmini.md)
|
||||
- [Lidar-Lite](sensor/lidar_lite.md)
|
||||
- [TeraRanger](sensor/teraranger.md)
|
||||
- [✘ Lanbao PSK-CM8JL65-CC5](sensor/cm8jl65_ir_distance_sensor.md)
|
||||
- [Avionics Anonymous Laser Altimeter UAVCAN Interface (CAN)](dronecan/avanon_laser_interface.md)
|
||||
- [GNSS (GPS)](gps_compass/index.md)
|
||||
- [ARK GPS (CAN)](dronecan/ark_gps.md)
|
||||
- [ARK DAN GPS](gps_compass/ark_dan_gps.md)
|
||||
- [ARK SAM GPS](gps_compass/ark_sam_gps.md)
|
||||
- [ARK SAM GPS MINI](gps_compass/ark_sam_gps_mini.md)
|
||||
- [ARK TESEO GPS](dronecan/ark_teseo_gps.md)
|
||||
- [CUAV NEO 3 GPS](gps_compass/gps_cuav_neo_3.md)
|
||||
- [CUAV NEO 3 Pro GPS (CAN)](gps_compass/gps_cuav_neo_3pro.md)
|
||||
@@ -271,8 +264,6 @@
|
||||
- [Sky-Drones SmartAP GPS](gps_compass/gps_smartap.md)
|
||||
- [RTK GNSS](gps_compass/rtk_gps.md)
|
||||
- [ARK RTK GPS (CAN)](dronecan/ark_rtk_gps.md)
|
||||
- [ARK RTK GPS L1 L5 (CAN)](dronecan/ark_rtk_gps_l1_l2.md)
|
||||
- [ARK X20 RTK GPS (CAN)](dronecan/ark_x20_rtk_gps.md)
|
||||
- [ARK MOSAIC-X5 RTK GPS (CAN)](dronecan/ark_mosaic__rtk_gps.md)
|
||||
- [RTK GPS Heading with Dual u-blox F9P](gps_compass/u-blox_f9p_heading.md)
|
||||
- [CUAV C-RTK](gps_compass/rtk_gps_cuav_c-rtk.md)
|
||||
@@ -350,14 +341,13 @@
|
||||
- [Battery Estimation Tuning](config/battery.md)
|
||||
- [Battery Chemistry Overview](power_systems/battery_chemistry.md)
|
||||
- [Power Modules/PDB](power_module/index.md)
|
||||
- [ARK PAB Power Module](power_module/ark_pab_power_module.md)
|
||||
- [ARK 12S PAB Power Module](power_module/ark_12s_pab_power_module.md)
|
||||
- [ARK 12S Payload Power Module](power_module/ark_12s_payload_power_module.md)
|
||||
- [CUAV HV pm](power_module/cuav_hv_pm.md)
|
||||
- [CUAV CAN PMU](dronecan/cuav_can_pmu.md)
|
||||
- [Holybro PM02](power_module/holybro_pm02.md)
|
||||
- [Holybro PM07](power_module/holybro_pm07_pixhawk4_power_module.md)
|
||||
- [Holybro PM06 V2](power_module/holybro_pm06_pixhawk4mini_power_module.md)
|
||||
- [ARK PAB Power Module](power_module/ark_pab_power_module.md)
|
||||
- [ARK 12S PAB Power Module](power_module/ark_12s_pab_power_module.md)
|
||||
- [Holybro PM02D (digital)](power_module/holybro_pm02d.md)
|
||||
- [Holybro PM03D (digital)](power_module/holybro_pm03d.md)
|
||||
- [Pomegranate Systems Power Module](dronecan/pomegranate_systems_pm.md)
|
||||
@@ -682,6 +672,8 @@
|
||||
- [RoverSpeedStatus](msg_docs/RoverSpeedStatus.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)
|
||||
- [RtlTimeEstimate](msg_docs/RtlTimeEstimate.md)
|
||||
@@ -703,7 +695,6 @@
|
||||
- [SensorOpticalFlow](msg_docs/SensorOpticalFlow.md)
|
||||
- [SensorPreflightMag](msg_docs/SensorPreflightMag.md)
|
||||
- [SensorSelection](msg_docs/SensorSelection.md)
|
||||
- [SensorTemp](msg_docs/SensorTemp.md)
|
||||
- [SensorUwb](msg_docs/SensorUwb.md)
|
||||
- [SensorsStatus](msg_docs/SensorsStatus.md)
|
||||
- [SensorsStatusImu](msg_docs/SensorsStatusImu.md)
|
||||
@@ -774,7 +765,6 @@
|
||||
- [Rpm Sensor](modules/modules_driver_rpm_sensor.md)
|
||||
- [Radio Control](modules/modules_driver_radio_control.md)
|
||||
- [Transponder](modules/modules_driver_transponder.md)
|
||||
- [adc](modules/modules_driver_adc.md)
|
||||
- [Estimators](modules/modules_estimator.md)
|
||||
- [Simulations](modules/modules_simulation.md)
|
||||
- [System](modules/modules_system.md)
|
||||
|
||||
@@ -10,13 +10,36 @@ By default, the [Missing Data](#missing-data-check), [Data Stuck](#data-stuck-ch
|
||||
You can configure which checks are active using the [ASPD_DO_CHECKS](#aspd_do_checks_table) parameter.
|
||||
:::
|
||||
|
||||
## Airspeed in PX4
|
||||
|
||||
PX4 handles multiple types of airspeed:
|
||||
|
||||
- **IAS (Indicated Airspeed):** The raw measurement from the airspeed sensor, directly influenced by sensor characteristics and installation effects (e.g., pitot-static errors).
|
||||
|
||||
- **CAS (Calibrated Airspeed):** IAS corrected for sensor-specific and installation-related errors.
|
||||
|
||||
- **EAS (Equivalent Airspeed):** _Not explicitly handled by PX4_ - Calibrated airspeed corrected for compressibility effects.
|
||||
While PX4 does not currently model EAS separately, this correction is negligible at low speeds and altitudes, so EAS is treated as equivalent to CAS for simplicity.
|
||||
|
||||
- **TAS (True Airspeed):** CAS adjusted for atmospheric effects such as air pressure and temperature (i.e., altitude and atmospheric conditions).
|
||||
|
||||
The standard conversion chain used in PX4 is: `IAS → CAS (= EAS) → TAS`.
|
||||
|
||||
## CAS Scale Estimation
|
||||
|
||||
Calibrated Airspeed (CAS) is the measured Indicated Airspeed (IAS) scaled to correct for sensor-specific and installation-related errors.
|
||||
CAS scaling plays an important role in keeping the [innovation check](#innovation-check) reliable, since a well-estimated CAS is key to spotting inconsistencies between measured and predicted airspeed.
|
||||
PX4 estimates the IAS to CAS scale (referred to as the CAS scale) during flight using GNSS ground speed and wind estimation.
|
||||
To compute the final TAS, standard environment conversions are applied (CAS → TAS).
|
||||
|
||||
This CAS scaling plays an important role in keeping the [innovation check](#innovation-check) reliable, since a well-estimated CAS is key to spotting inconsistencies between measured and predicted airspeed.
|
||||
If the estimated CAS scale is inaccurate, it can mask real airspeed faults or trigger false positives.
|
||||
|
||||
If you observe that the CAS scale estimate is consistently off, or if it is converging too slowly, follow the steps outlined in [Airspeed Scale Handling](../config_fw/airspeed_scale_handling.md#recommended-first-flight-process).
|
||||
If you observe that the CAS scale estimate is consistently off, or if it is converging too slowly, you can manually set it using [ASPD_SCALE_n](#aspd_scale_n_table) (where `n` is the sensor number).
|
||||
[ASPD_SCALE_APPLY](#aspd_scale_apply_table) can be used to configure when/if the estimated scale is applied.
|
||||
|
||||
::: info
|
||||
For a quick manual CAS scale estimate, compare groundspeed minus windspeed (from the [VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) and [Wind](../msg_docs/Wind.md) messages, respectively) to indicated airspeed values (in the [Airspeed](../msg_docs/Airspeed.md) message).
|
||||
The ratio of indicated airspeed to groundspeed minus windspeed can provide a reasonable starting estimate for [ASPD_SCALE_n](#aspd_scale_n_table).
|
||||
:::
|
||||
|
||||
## Validation Checks
|
||||
|
||||
|
||||
@@ -10,48 +10,6 @@ If a listed parameter is missing from the Firmware see: [Finding/Updating Parame
|
||||
|
||||
<!-- markdown generator: src/lib/parameters/px4params/markdownout.py -->
|
||||
|
||||
## ADC
|
||||
|
||||
### ADC_ADS7953_EN (`INT32`) {#ADC_ADS7953_EN}
|
||||
|
||||
Enable ADS7953.
|
||||
|
||||
Enable the driver for the ADS7953 board
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------------ | ---- |
|
||||
| ✓ | | | | Disabled (0) |
|
||||
|
||||
### ADC_ADS7953_REFV (`FLOAT`) {#ADC_ADS7953_REFV}
|
||||
|
||||
Applied reference Voltage.
|
||||
|
||||
The voltage applied to the ADS7953 board as reference
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------- | ---- |
|
||||
| ✓ | 2.0 | 3.0 | 0.01 | 2.5 | V |
|
||||
|
||||
### ADC_TLA2528_EN (`INT32`) {#ADC_TLA2528_EN}
|
||||
|
||||
Enable TLA2528.
|
||||
|
||||
Enable the driver for the TLA2528
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------------ | ---- |
|
||||
| ✓ | | | | Disabled (0) |
|
||||
|
||||
### ADC_TLA2528_REFV (`FLOAT`) {#ADC_TLA2528_REFV}
|
||||
|
||||
Applied reference Voltage.
|
||||
|
||||
The voltage applied to the TLA2528 board as reference
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------- | ---- |
|
||||
| ✓ | 2.0 | 3.0 | 0.01 | 2.5 | V |
|
||||
|
||||
## ADSB
|
||||
|
||||
### ADSB_CALLSIGN_1 (`INT32`) {#ADSB_CALLSIGN_1}
|
||||
@@ -13997,9 +13955,9 @@ Scale of airspeed sensor 1.
|
||||
|
||||
This is the scale IAS --> CAS of the first airspeed sensor instance
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 0.5 | 2.0 | | 1.0 |
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------- | ---- |
|
||||
| ✓ | 0.5 | 2.0 | | 1.0 |
|
||||
|
||||
### ASPD_SCALE_2 (`FLOAT`) {#ASPD_SCALE_2}
|
||||
|
||||
@@ -14007,9 +13965,9 @@ Scale of airspeed sensor 2.
|
||||
|
||||
This is the scale IAS --> CAS of the second airspeed sensor instance
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 0.5 | 2.0 | | 1.0 |
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------- | ---- |
|
||||
| ✓ | 0.5 | 2.0 | | 1.0 |
|
||||
|
||||
### ASPD_SCALE_3 (`FLOAT`) {#ASPD_SCALE_3}
|
||||
|
||||
@@ -14017,9 +13975,9 @@ Scale of airspeed sensor 3.
|
||||
|
||||
This is the scale IAS --> CAS of the third airspeed sensor instance
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 0.5 | 2.0 | | 1.0 |
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------- | ---- |
|
||||
| ✓ | 0.5 | 2.0 | | 1.0 |
|
||||
|
||||
### ASPD_SCALE_APPLY (`INT32`) {#ASPD_SCALE_APPLY}
|
||||
|
||||
@@ -17207,9 +17165,7 @@ Set bits in the following positions to enable: 0 : Longitude and latitude fusion
|
||||
|
||||
### EKF2_GPS_DELAY (`FLOAT`) {#EKF2_GPS_DELAY}
|
||||
|
||||
GPS measurement delay relative to IMU measurement.
|
||||
|
||||
GPS measurement delay relative to IMU measurement if PPS time correction is not available/enabled (PPS_CAP_ENABLE).
|
||||
GPS measurement delay relative to IMU measurements.
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------- | ---- |
|
||||
@@ -17219,7 +17175,7 @@ GPS measurement delay relative to IMU measurement if PPS time correction is not
|
||||
|
||||
Fusion reset mode.
|
||||
|
||||
Automatic: reset on fusion timeout if no other source of position is available. Dead-reckoning: reset on fusion timeout if no source of velocity is available.
|
||||
Automatic: reset on fusion timeout if no other source of position is available Dead-reckoning: reset on fusion timeout if no source of velocity is available
|
||||
|
||||
**Values:**
|
||||
|
||||
@@ -33149,14 +33105,6 @@ Maxbotix Sonar (mb12xx).
|
||||
| ------- | -------- | -------- | --------- | ------------ | ---- |
|
||||
| ✓ | | | | Disabled (0) |
|
||||
|
||||
### SENS_EN_MCP9808 (`INT32`) {#SENS_EN_MCP9808}
|
||||
|
||||
Enable MCP9808 temperature sensor (external I2C).
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------- | -------- | -------- | --------- | ------------ | ---- |
|
||||
| ✓ | | | | Disabled (0) |
|
||||
|
||||
### SENS_EN_MPDT (`INT32`) {#SENS_EN_MPDT}
|
||||
|
||||
Enable Mappydot rangefinder (i2c).
|
||||
@@ -39484,14 +39432,6 @@ Maximum time (in seconds) before resetting setpoint.
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | | | | 2.0 |
|
||||
|
||||
### UUV_STICK_MODE (`INT32`) {#UUV_STICK_MODE}
|
||||
|
||||
Stick mode selector (0=Heave/sway control, roll/pitch leveled; 1=Pitch/roll control).
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 0 | 1 | | 0 |
|
||||
|
||||
### UUV_THRUST_SAT (`FLOAT`) {#UUV_THRUST_SAT}
|
||||
|
||||
UUV Thrust setpoint Saturation.
|
||||
@@ -40195,7 +40135,7 @@ Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.
|
||||
|
||||
### VT_B_DEC_I (`FLOAT`) {#VT_B_DEC_I}
|
||||
|
||||
Backtransition deceleration setpoint to tilt I gain.
|
||||
Backtransition deceleration setpoint to pitch I gain.
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ------- |
|
||||
@@ -40413,7 +40353,7 @@ During landing it can be beneficial to reduce the pitch angle to reduce the gene
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | -10.0 | 45.0 | 0.1 | 0.0 | deg |
|
||||
| | -10.0 | 45.0 | 0.1 | -5.0 | deg |
|
||||
|
||||
### VT_PITCH_MIN (`FLOAT`) {#VT_PITCH_MIN}
|
||||
|
||||
@@ -40424,7 +40364,7 @@ VT_FWD_TRHUST_EN is set.
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | -10.0 | 45.0 | 0.1 | 0.0 | deg |
|
||||
| | -10.0 | 45.0 | 0.1 | -5.0 | deg |
|
||||
|
||||
### VT_PSHER_SLEW (`FLOAT`) {#VT_PSHER_SLEW}
|
||||
|
||||
|
||||
@@ -52,17 +52,19 @@ RC controllers will use different sticks for throttle and yaw [based on their mo
|
||||
- _Arm:_ Left-stick to right, right-stick to bottom.
|
||||
- _Disarm:_ Left-stick to left, right-stick to the bottom.
|
||||
|
||||
The required hold time can be configured using [COM_RC_ARM_HYST](#COM_RC_ARM_HYST).
|
||||
Note that by default ([COM_DISARM_MAN](#COM_DISARM_MAN)) you can also disarm in flight using gestures/buttons: you may choose to disable this to avoid accidental disarming.
|
||||
|
||||
| Parameter | Description |
|
||||
| -------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="MAN_ARM_GESTURE"></a>[MAN_ARM_GESTURE](../advanced_config/parameter_reference.md#MAN_ARM_GESTURE) | Enable arm/disarm stick guesture. `0`: Disabled, `1`: Enabled (default). |
|
||||
| <a id="COM_DISARM_MAN"></a>[COM_DISARM_MAN](../advanced_config/parameter_reference.md#COM_DISARM_MAN) | Enable disarming in flight via switch/stick/button in MC manual thrust modes. `0`: Disabled, `1`: Enabled (default). |
|
||||
| <a id="COM_RC_ARM_HYST"></a>[COM_RC_ARM_HYST](../advanced_config/parameter_reference.md#COM_RC_ARM_HYST) | Time that RC stick must be held in arm/disarm position before arming/disarming occurs (default: `1` second). |
|
||||
|
||||
## Arming Button/Switch {#arm_disarm_switch}
|
||||
|
||||
An _arming button_ or "momentary switch" can be configured to trigger arm/disarm _instead_ of [gesture-based arming](#arm_disarm_gestures) (setting an arming switch disables arming gestures).
|
||||
The button should be held down for one second to arm (when disarmed) or disarm (when armed).
|
||||
The button should be held down for ([nominally](#COM_RC_ARM_HYST)) one second to arm (when disarmed) or disarm (when armed).
|
||||
|
||||
A two-position switch can also be used for arming/disarming, where the respective arm/disarm commands are sent on switch _transitions_.
|
||||
|
||||
@@ -75,7 +77,7 @@ The switch or button is assigned (and enabled) using [RC_MAP_ARM_SW](#RC_MAP_ARM
|
||||
| Parameter | Description |
|
||||
| -------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="RC_MAP_ARM_SW"></a>[RC_MAP_ARM_SW](../advanced_config/parameter_reference.md#RC_MAP_ARM_SW) | RC arm switch channel (default: 0 - unassigned). If defined, the specified RC channel (button/switch) is used for arming instead of a stick gesture. <br>**Note:**<br>- This setting _disables the stick gesture_!<br>- This setting applies to RC controllers. It does not apply to Joystick controllers that are connected via _QGroundControl_. |
|
||||
| <a id="COM_ARM_SWISBTN"></a>[COM_ARM_SWISBTN](../advanced_config/parameter_reference.md#COM_ARM_SWISBTN) | Arm switch is a momentary button. <br>- `0`: Arm switch is a 2-position switch where arm/disarm commands are sent on switch transitions.<br>-`1`: Arm switch is a momentary button where the arm/disarm command is sent after holding down the button for one second. |
|
||||
| <a id="COM_ARM_SWISBTN"></a>[COM_ARM_SWISBTN](../advanced_config/parameter_reference.md#COM_ARM_SWISBTN) | Arm switch is a momentary button. <br>- `0`: Arm switch is a 2-position switch where arm/disarm commands are sent on switch transitions.<br>-`1`: Arm switch is a button or momentary button where the arm/disarm command ae sent after holding down button for set time ([COM_RC_ARM_HYST](#COM_RC_ARM_HYST)). |
|
||||
|
||||
::: info
|
||||
The switch can also be set as part of _QGroundControl_ [Flight Mode](../config/flight_mode.md) configuration.
|
||||
|
||||
@@ -348,60 +348,6 @@ The `hpos_drift_rate`, `vpos_drift_rate` and `hspd` are calculated over a period
|
||||
Note that `ekf2_gps_drift` is not logged!
|
||||
:::
|
||||
|
||||
#### GNSS Fault Detection
|
||||
|
||||
PX4's GNSS fault detection protects against malicious or erroneous GNSS signals using selective fusion control based on measurement validation.
|
||||
|
||||
The fault detection logic depends on the GPS mode, and also operates differently for horizontal position and altitude measurements.
|
||||
The mode is set using the [EKF2_GPS_MODE](../advanced_config/parameter_reference.md#EKF2_GPS_MODE) parameter:
|
||||
|
||||
- **Automatic (`0`)** (Default): Assumes that GNSS is generally reliable and is likely to be recovered.
|
||||
EKF2 resets on fusion timeouts if no other source of position is available.
|
||||
- **Dead-reckoning (`1`)**: Assumes that GNSS might be lost indefinitely, so resets should be avoided while we have other estimates of position data.
|
||||
EKF2 may reset if no other sources of position or velocity are available.
|
||||
If GNSS altitude OR horizontal position data drifts, the system disables fusion of both measurements simultaneously (even if one would still pass validation) and avoids performing resets.
|
||||
|
||||
##### Detection Logic
|
||||
|
||||
Horizontal Position:
|
||||
|
||||
- **Automatic mode**: Horizontal position resets to GNSS data if no other horizontal position source is currently being fused (e.g., Auxiliary Global Position - AGP).
|
||||
- **Dead-reckoning mode**: Horizontal position resets to GNSS data only if no other horizontal position OR velocity source is currently being fused (e.g., AGP, airspeed, optical flow).
|
||||
|
||||
Altitude:
|
||||
|
||||
- The altitude logic is more complex due to the height reference sensor ([EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF)) parameter, which is typically set to GNSS or baro in GNSS-denied scenarios.
|
||||
- If height reference is set to baro, GNSS-based height resets are prevented (except when baro fusion fails completely and height reference automatically switches to GNSS).
|
||||
- When height reference is set to GNSS:
|
||||
- **Automatic mode**: Resets occur on drifting GNSS altitude measurements.
|
||||
- **Dead-reckoning mode**: When validation starts failing, the system prevents GNSS altitude resets and labels the GNSS data as faulty.
|
||||
|
||||
##### Faulty GNSS Data During Boot
|
||||
|
||||
The system cannot automatically detect faulty GNSS data during vehicle boot as no baseline comparison exists.
|
||||
|
||||
If GNSS fusion is enabled ([EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL)), operators will observe incorrect positions on maps and should disable GNSS fusion, then manually set the correct position via ground control station.
|
||||
The global position gets corrected, and if [SENS_BAR_AUTOCAL](../advanced_config/parameter_reference.md#SENS_BAR_AUTOCAL) was enabled, baro offsets are automatically adjusted (through bias correction, not parameter changes).
|
||||
|
||||
##### Enabling GNSS Fusion Mid-Flight
|
||||
|
||||
With Faulty GNSS Data:
|
||||
|
||||
- **Automatic mode**: Vehicle will reset to faulty position - potentially dangerous.
|
||||
- **Dead-reckoning mode**: Large measurement differences cause GNSS rejection and fault detection activation.
|
||||
|
||||
With Valid GNSS Data:
|
||||
|
||||
- **Automatic mode**: Vehicle will reset to GNSS measurements.
|
||||
- **Dead-reckoning mode**: If estimated position/altitude is close enough to measurements, fusion resumes; if too far apart, data gets labeled as faulty.
|
||||
|
||||
##### Notes
|
||||
|
||||
- **Dual Detection**: Horizontal and altitude checks run completely separately but both lead to the same result when triggered - all GNSS fusion gets disabled.
|
||||
- **Recovery**: Only the specific check that labeled data as invalid can re-enable fusion.
|
||||
- **Alternative Sources**: Dead-reckoning mode provides enhanced protection by requiring absence of alternative navigation sources before allowing resets.
|
||||
- **Boot Vulnerability**: Initial faulty GNSS data cannot be detected automatically; requires operator intervention and manual position correction.
|
||||
|
||||
### Range Finder
|
||||
|
||||
[Range finder](../sensor/rangefinders.md) distance to ground is used by a single state filter to estimate the vertical position of the terrain relative to the height datum.
|
||||
|
||||
@@ -160,7 +160,6 @@ The fields are:
|
||||
[Generally you should use the default actuator value](#actuator-roll-pitch-and-yaw-scaling).
|
||||
- `Trim`: An offset added to the actuator so that it is centered without input.
|
||||
This might be determined by trial and error.
|
||||
Prefer using the improved `PWM_CENT` instead: [PWM control surfaces](actuators.md#pwm-control-surfaces-that-move-both-directions-about-a-neutral-point).
|
||||
- <a id="slew_rate"></a>(Advanced) `Slew Rate`: Limits the minimum time in which the motor/servo signal is allowed to pass through its full output range, in seconds.
|
||||
- The setting limits the rate of change of an actuator (if not specified then no rate limit is applied).
|
||||
It is intended for actuators that may be damaged or cause flight disturbance if they move too fast — such as the tilting actuators on a tiltrotor VTOL vehicle, or fast moving flaps, respectively.
|
||||
@@ -536,41 +535,12 @@ If you're using PWM servos, PWM50 is far more common.
|
||||
If a high rate servo is _really_ needed, DShot offers better value.
|
||||
:::
|
||||
|
||||
##### PWM: Control surfaces that move both directions about a neutral point
|
||||
|
||||
To facilitate setting the neutral point of the servos, a bilinear curve function can be defined using the following parameters `PWM_MAIN_CENTx` / `PWM_AUX_CENTx` for each servo. This allows for unequal deflections in the positive and negative direction:
|
||||
|
||||

|
||||
|
||||
To set this up:
|
||||
|
||||
1. Set all surface `Trim` to `0.00` for all surfaces:
|
||||
|
||||

|
||||
|
||||
2. Set the `PWM_MAIN_CENTx` / `PWM_AUX_CENTx` value so that the surface will stay at the neutral (aligned with airfoil) position.
|
||||
This is usually around `1500` for PWM servos (near the center of the servo range).
|
||||
|
||||

|
||||
|
||||
3. Gradually increase the `Maximum` for each servo until the desired deflection is reached. Check the deflection with a remote manual mode while [`COM_PREARM_MODE`](../advanced_config/parameter_reference.md#COM_PREARM_MODE) is set to `Always` or use the sliders.
|
||||
4. Gradually decrease the `Minimum` for each servo, until the desired deflection is reached.
|
||||
5. Set `Disarmed` value to the desired value. It is usually desirable to have it the same as the `Center` value.
|
||||
|
||||
::: info
|
||||
If you want to retain the linear behaviour of the servo after setting the `Center`, make sure to adjust the `Minimum` or `Maximum`, such that both intervals (`min` to `cent` & `cent` to `max`) are equally large.
|
||||
|
||||

|
||||
:::
|
||||
|
||||
#### Non-PWM: Control surfaces that move both directions about a neutral point
|
||||
#### Control surfaces that move both directions about a neutral point
|
||||
|
||||
Control surfaces that move either direction around a neutral point include: ailerons, elevons, V-tails, A-tails, and rudders.
|
||||
|
||||
To set these up:
|
||||
|
||||
0. Set all `PWM_MAIN_CENTx` and `PWM_AUX_CENTx` to default (-1), or trimming will not be possible.
|
||||
|
||||
1. Set the `Disarmed` value so that the surfaces will stay at neutral position when disarmed.
|
||||
This is usually around `1500` for PWM servos (near the centre of the servo range).
|
||||
|
||||
@@ -589,17 +559,14 @@ To set these up:
|
||||
3. Move the slider again to the middle and check if the Control Surfaces are aligned in the neutral position of the wing.
|
||||
- If it is not aligned, you can set the **Trim** value for the control surface.
|
||||
|
||||
::: info
|
||||
This is done in the `Trim` setting of the Geometry panel, usually by "trial and error".
|
||||

|
||||
:::
|
||||
::: info
|
||||
This is done in the `Trim` setting of the Geometry panel, usually by "trial and error".
|
||||

|
||||
:::
|
||||
|
||||
- After setting the trim for a control surface, move its slider away from the centre, release, and then back into disarmed (middle) position.
|
||||
Confirm that surface is in the neutral position.
|
||||
|
||||
::: tip
|
||||
If any servo has a `PWM_MAIN_CENTx` or `PWM_AUX_CENTx` not set to default (-1), the system will automatically remove `Trim` from all surfaces. This is done to prevent mixing of old and new trimming tools.
|
||||
:::
|
||||
|
||||
::: info
|
||||
Another way to test without using the sliders would be to set the [`COM_PREARM_MODE`](../advanced_config/parameter_reference.md#COM_PREARM_MODE) parameter to `Always`:
|
||||
|
||||
@@ -618,7 +585,6 @@ For a flap, that is when the flap is fully retracted and flush with the wing.
|
||||
|
||||
One approach for setting these up is:
|
||||
|
||||
0. Set all `PWM_MAIN_CENTx` and `PWM_AUX_CENTx` to default (-1), or trimming will not be possible.
|
||||
1. Set values `Disarmed` to `1500`, `Min` to `1200`, `Max` to `1700` so that the values are around the centre of the servo range.
|
||||
2. Move the corresponding slider up and check the control moves and that it is extending (moving away from the disarmed position).
|
||||
If not, click on the `Rev Range` checkbox to reverse the range.
|
||||
@@ -628,7 +594,6 @@ One approach for setting these up is:
|
||||
- If the value was increased towards `Max`, then set `Max` to match `Disarmed`.
|
||||
4. The value that you did _not_ set to match `Disarmed` controls the maximum amount that the control surface can extend.
|
||||
Set the slider to the top of the control, then change the value (`Max` or `Min`) so that the control surface is fully extended when the slider is at top.
|
||||
5. (Only PWM servos) Set the `Center` value to the middle between `Min` and `Max`.
|
||||
|
||||
::: info Special note for flaps
|
||||
In some vehicle builds, flaps may be configured such that both flaps are controlled from a single output.
|
||||
@@ -666,11 +631,6 @@ For each of the tilt servos:
|
||||
- Standard VTOL : Motors defined as multicopter motors will be turned off
|
||||
- Tiltrotors : Motors that have no associated tilt servo will turn off
|
||||
- Tailsitters do not turn off any motors in fixed-wing flight
|
||||
- The following formula can be used to migrate from surface trim to PWM trim:
|
||||
|
||||
```plain
|
||||
PWM_MAIN_CENTx = ((PWM_MAX - PWM_MIN) / 2) * CA_SV_CSx_TRIM + PWM_MIN + ((PWM_MAX - PWM_MIN) / 2)
|
||||
```
|
||||
|
||||
### Reversing Motors
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@ Most users should set the following modes and functions, as these make the vehic
|
||||
It is also common to map switches to:
|
||||
|
||||
- **Mission mode** — This mode runs a pre-programmed mission sent by the ground control station.
|
||||
- <a id="kill_switch"></a> [Kill Switch](../config/safety.md#kill-switch) - Immediately stops all motor outputs (the vehicle will crash, which may in some circumstances be more desirable than allowing it to continue flying).
|
||||
- <a id="emergency_stop_switch"></a> [Kill Switch](../config/safety.md#kill-switch) - Immediately stops all motor outputs (the vehicle will crash, which may in some circumstances be more desirable than allowing it to continue flying).
|
||||
|
||||
## Flight Mode Selection
|
||||
|
||||
@@ -49,7 +49,7 @@ To configure single-channel flight mode selection:
|
||||
* Select the flight mode that you want triggered for each switch position.
|
||||
1. Specify *Switch Settings*:
|
||||
* Select the channels that you want to map to specific actions - e.g.: *Return* mode, *Kill switch*, *offboard* mode, etc. (if you have spare switches and channels on your transmitter).
|
||||
|
||||
|
||||
1. Test that the modes are mapped to the right transmitter switches:
|
||||
* Check the *Channel Monitor* to confirm that the expected channel is changed by each switch.
|
||||
* Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on *QGroundControl* for the active mode).
|
||||
|
||||
@@ -1,104 +0,0 @@
|
||||
# Airspeed Scale Handling
|
||||
|
||||
::: info
|
||||
This section complements the existing [Airspeed Validation](../advanced_config/airspeed_validation.md) documentation.
|
||||
:::
|
||||
|
||||
The airspeed scale is used by PX4 to convert the measured airspeed (indicated airspeed) to the calibrated airspeed.
|
||||
This scale can be set by [ASPD_SCALE_n](../advanced_config/parameter_reference.md#ASPD_SCALE_1) (where `n` is the sensor number), and logged in [AirspeedWind.msg](../msg_docs/AirspeedWind.md).
|
||||
|
||||
Note that the airspeed scale is different from the airspeed sensor offset calibration done on the ground at 0 m/s. The airspeed scale accounts for errors in the airspeed measurement during flight, such as those caused by sensor placement or installation effects.
|
||||
|
||||
This topic describes how to set an initial airspeed scale for a new fixed-wing vehicle during its first flight. Correct scale calibration ensures reliable airspeed data, accurate TAS calculation, robust PX4 airspeed validation, and consistent controller performance.
|
||||
|
||||
## Airspeed in PX4
|
||||
|
||||
PX4 handles multiple types of airspeed:
|
||||
|
||||
- **IAS (Indicated Airspeed):** The raw measurement from the airspeed sensor, directly influenced by sensor characteristics and installation effects (e.g., pitot-static errors).
|
||||
- **CAS (Calibrated Airspeed):** IAS corrected for sensor-specific and installation-related errors.
|
||||
- **EAS (Equivalent Airspeed):** _Not explicitly handled by PX4_ - Calibrated airspeed corrected for compressibility effects.
|
||||
While PX4 does not currently model EAS separately, this correction is negligible at low speeds and altitudes, so EAS is treated as equivalent to CAS for simplicity.
|
||||
- **TAS (True Airspeed):** CAS adjusted for atmospheric effects such as air pressure and temperature (i.e., altitude and atmospheric conditions).
|
||||
|
||||
The standard conversion chain used in PX4 is: `IAS → CAS (= EAS) → TAS`.
|
||||
|
||||
## CAS Scale Estimation
|
||||
|
||||
PX4 estimates the IAS to CAS scale (referred to as the CAS scale) during flight using GNSS ground speed and wind estimation.
|
||||
To compute the final TAS, standard environment conversions are applied (CAS → TAS).
|
||||
|
||||
:::warning Important
|
||||
A GNSS is required for scale estimation.
|
||||
:::
|
||||
|
||||
PX4 uses a two-stage approach to robustly estimate the scale:
|
||||
|
||||
1. **Continuous EKF Estimation**: A wind estimator constantly compares your measured airspeed against what it expects based on ground velocity (from GNSS) and estimated wind.
|
||||
If there's a consistent bias, it adjusts the scale estimate.
|
||||
The estimated scale is logged in the `AirspeedWind.msg` as the `tas_scale_raw`.
|
||||
2. **Validation**: To ensure robustness, PX4 collects airspeed and ground speed data across 12 different heading segments (every 30°).
|
||||
This averages out wind estimation errors.
|
||||
The validated scale is only updated when the new estimate demonstrably reduces the error between predicted and actual ground speeds across all headings.
|
||||
The validated scale is logged in the `AirspeedWind.msg` as the `tas_scale_validated`.
|
||||
|
||||
### Understanding the Scale: Physical Intuition
|
||||
|
||||
The CAS scale is essentially a correction factor that accounts for systematic errors in your airspeed sensor installation.
|
||||
|
||||
- A scale of 1.0 means your sensor reads perfectly (no correction needed)
|
||||
- A scale > 1.0 (e.g., 1.1) means your sensor _under-reads_ by 10%, so measured airspeed (IAS) must be multiplied by 1.1
|
||||
- A scale < 1.0 (e.g., 0.9) means your sensor _over-reads_ by ~11%, so measured airspeed (IAS) must be multiplied by 0.9
|
||||
|
||||
### What Affects the Airspeed Scale
|
||||
|
||||
The primary factor influencing the airspeed scale is **sensor placement**.
|
||||
|
||||
Biased readings can be reflected in the scale estimate for pitot tubes installed:
|
||||
|
||||
- In regions experiencing disturbed flow (commonly near blunt aircraft noses)
|
||||
- Near propellers
|
||||
- Under aerodynamic surfaces
|
||||
- At an angle with respect to the airflow
|
||||
|
||||
### Symptoms of Incorrect Scale
|
||||
|
||||
Symptoms of an incorrectly scaled airspeed measurement include:
|
||||
|
||||
- Stalling or overspeeding
|
||||
- Persistent under- or overestimation of the TAS relative to wind-corrected groundspeed
|
||||
- False positives or missed detections in [airspeed innovation checks](../advanced_config/airspeed_validation.md#innovation-check)
|
||||
- Degraded tracking of the rate controllers
|
||||
|
||||
## Recommended First Flight Process
|
||||
|
||||
During the first flight of a new fixed-wing vehicle, allocate time for the CAS scale to converge to a reasonable initial estimate.
|
||||
Follow these steps:
|
||||
|
||||
1. **Set an Initial Scale**
|
||||
|
||||
Use a conservative starting point: set the CAS scale (`ASPD_SCALE_n`) slightly under 1.0 (for example 0.95).
|
||||
This biases the system toward over-speed rather than under-speed, reducing stall risk.
|
||||
|
||||
2. **Perform a Flight**
|
||||
|
||||
After takeoff, place the vehicle in loiter for about 15 minutes to allow the scale estimation to converge.
|
||||
|
||||
3. **Check Scale Convergence**
|
||||
|
||||
After the flight, review the estimated scale in logs.
|
||||
Verify that:
|
||||
- `tas_scale_validated` in `AirspeedWind.msg` converged during flight.
|
||||
- `true_airspeed_m_s` (TAS) in [AirspeedValidated.msg](../msg_docs/AirspeedValidated.md) is consistent with groundspeed corrected for wind.
|
||||
|
||||
4. **Update the Airframe Configuration**
|
||||
|
||||
If using an [airframe configuration file](../dev_airframes/adding_a_new_frame.md): update `ASPD_SCALE_n`with the estimated CAS scale for future flights.
|
||||
For similar vehicles with similarly mounted sensors, this value is typically a reliable starting point.
|
||||
|
||||
::: info
|
||||
If you are not able to perform the steps outlined above ...
|
||||
|
||||
For a quick manual CAS scale estimate, compare groundspeed minus windspeed (from the [VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) and [Wind](../msg_docs/Wind.md) messages, respectively) to indicated airspeed values (in the [Airspeed](../msg_docs/Airspeed.md) message).
|
||||
The ratio of indicated airspeed to groundspeed minus windspeed can provide a reasonable starting estimate for `ASPD_SCALE_n`.
|
||||
:::
|
||||
@@ -3,7 +3,7 @@
|
||||
Fixed-wing configuration and calibration follows the same high level steps as other frames: selection of firmware, configuration of the frame including actuator/motor geometry and output mappings, sensor configuration and calibration, configuration of safety and other features, and finally tuning.
|
||||
|
||||
::: info
|
||||
This topic is the recommended entry point when performing first-time configuration and calibration of a new fixed-wing frame.
|
||||
This topic is the recommended entry point when performing first-time configuration and calibration of a new multicopter frame.
|
||||
:::
|
||||
|
||||
The main steps are:
|
||||
@@ -17,4 +17,3 @@ The main steps are:
|
||||
|
||||
- [Fixed-wing Altitude/Position Controller Tuning Guide](../config_fw/position_tuning_guide_fixedwing.md)
|
||||
- [Fixed-wing Trimming Guide](../config_fw/trimming_guide_fixedwing.md)
|
||||
- [Fixed-Wing Airspeed Scale Handling](../config_fw/airspeed_scale_handling.md)
|
||||
|
||||
@@ -17,8 +17,6 @@ Manual tuning is recommended for frames where autotuning does not work, or where
|
||||
- Excessive gains (and rapid servo motion) can violate the maximum forces of your airframe - increase gains carefully.
|
||||
- Roll and pitch tuning follow the same sequence.
|
||||
The only difference is that pitch is more sensitive to trim offsets, so [trimming](../config_fw/trimming_guide_fixedwing.md) has to be done carefully and integrator gains need more attention to compensate this.
|
||||
- Disable automatic [gain compression](../features_fw/gain_compression.md) ([FW_GC_EN](../advanced_config/parameter_reference.md#FW_GC_EN)) to avoid over-tuning.
|
||||
Remember to re-enable it when tuning is done.
|
||||
|
||||
## Establishing the Airframe Baseline
|
||||
|
||||
|
||||
@@ -88,7 +88,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
|
||||
|
||||
One approach to determine an appropriate value is:
|
||||
1. From a standstill, give the rover full throttle until it reaches the maximum speed.
|
||||
2. Disarm the rover and plot the `measured_speed_body_x` from [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md).
|
||||
2. Disarm the rover and plot the `measured_speed_body_x` from [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md).
|
||||
3. Divide the maximum speed by the time it took to reach it and set this as the value for [RO_ACCEL_LIM](#RO_ACCEL_LIM).
|
||||
|
||||
Some RC rovers have enough torque to lift up if the maximum acceleration is not limited.
|
||||
|
||||
@@ -19,6 +19,7 @@ To tune the position controller configure the [parameters](../advanced_config/pa
|
||||
$v*{max} = v*{full throttle} \cdot (1 - \theta\_{normalized} \cdot k) $
|
||||
|
||||
with
|
||||
|
||||
- $v_{max}:$ Maximum speed
|
||||
- $v_{full throttle}:$ Speed at maximum throttle [RO_MAX_THR_SPEED](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED).
|
||||
- $\theta_{normalized}:$ Course error (Course - bearing setpoint) normalized from $[0\degree, 180\degree]$ to $[0, 1]$
|
||||
@@ -33,13 +34,14 @@ To tune the position controller configure the [parameters](../advanced_config/pa
|
||||
|
||||
::: tip
|
||||
Plan a mission for the rover to drive a square and observe how it slows down when approaching a waypoint:
|
||||
|
||||
- If the rover decelerates too quickly decrease the [RO_DECEL_LIM](../advanced_config/parameter_reference.md#RO_DECEL_LIM) parameter, if it starts slowing down too early increase the parameter.
|
||||
- If you observe a jerking motion as the rover slows down, decrease the [RO_JERK_LIM](../advanced_config/parameter_reference.md#RO_JERK_LIM) parameter otherwise increase it as much as possible as it can interfere with the tuning of [RO_DECEL_LIM](../advanced_config/parameter_reference.md#RO_DECEL_LIM).
|
||||
|
||||
These two parameters have to be tuned as a pair, repeat until you are satisfied with the behaviour.
|
||||
:::
|
||||
|
||||
3. Plot the `adjusted_speed_body_x_setpoint` and `measured_speed_body_x` from the [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) message over each other.
|
||||
3. Plot the `adjusted_speed_body_x_setpoint` and `measured_speed_body_x` from the [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md) message over each other.
|
||||
If the tracking of these setpoints is not satisfactory adjust the values for [RO_SPEED_P](../advanced_config/parameter_reference.md#RO_SPEED_P) and [RO_SPEED_I](../advanced_config/parameter_reference.md#RO_SPEED_I).
|
||||
|
||||
## Path Following
|
||||
@@ -55,6 +57,7 @@ The following parameters are used to tune the algorithm:
|
||||
Decreasing the parameter makes it more aggressive but can lead to oscillations.
|
||||
|
||||
To tune this:
|
||||
|
||||
1. Start with a value of 1 for [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN)
|
||||
2. Put the rover in [Position mode](../flight_modes_rover/manual.md#position-mode) and while driving a straight line at approximately half the maximum speed observe its behaviour.
|
||||
3. If the rover does not drive in a straight line, reduce the value of the parameter, if it oscillates around the path increase the value.
|
||||
|
||||
@@ -23,10 +23,11 @@ To tune the velocity controller configure the following [parameters](../advanced
|
||||
|
||||
::: tip
|
||||
To further tune this parameter:
|
||||
|
||||
1. Set [RO_SPEED_P](#RO_SPEED_P) and [RO_SPEED_I](#RO_SPEED_I) to zero.
|
||||
This way the speed is only controlled by the feed-forward term, which makes it easier to tune.
|
||||
2. Put the rover in [Position mode](../flight_modes_rover/manual.md#position-mode) and then move the left stick of your controller up and/or down and hold it at a few different levels for a couple of seconds each.
|
||||
3. Disarm the rover and from the flight log plot the `adjusted_speed_body_x_setpoint` and the `measured_speed_body_x` from the [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) message over each other.
|
||||
3. Disarm the rover and from the flight log plot the `adjusted_speed_body_x_setpoint` and the `measured_speed_body_x` from the [RoverVelocityStatus](../msg_docs/RoverVelocityStatus.md) message over each other.
|
||||
4. If the actual speed of the rover is higher than the speed setpoint, increase [RO_MAX_THR_SPEED](#RO_MAX_THR_SPEED).
|
||||
If it is the other way around decrease the parameter and repeat until you are satisfied with the setpoint tracking.
|
||||
|
||||
@@ -63,6 +64,7 @@ These steps are only necessary if you are tuning/want to unlock the manual [Posi
|
||||
Decreasing the parameter makes it more aggressive but can lead to oscillations.
|
||||
|
||||
To tune this:
|
||||
|
||||
1. Start with a value of 1 for [PP_LOOKAHD_GAIN](#PP_LOOKAHD_GAIN)
|
||||
2. Put the rover in [Position mode](../flight_modes_rover/manual.md#position-mode) and while driving a straight line at approximately half the maximum speed observe its behaviour.
|
||||
3. If the rover does not drive in a straight line, reduce the value of the parameter, if it oscillates around the path increase the value.
|
||||
|
||||
@@ -215,7 +215,7 @@ Predefined information messages are:
|
||||
| `char[value_len] ver_sw_branch` | git branch | "master" |
|
||||
| `uint32_t ver_sw_release` | Software version (see below) | 0x010401ff |
|
||||
| `char[value_len] sys_os_name` | Operating System Name | "Linux" |
|
||||
| `char[value_len] sys_os_ver` | OS version (git tag) | "9f82919" |
|
||||
| `char[value_len] sys_os_ve`r | OS version (git tag) | "9f82919" |
|
||||
| `uint32_t ver_os_release` | OS version (see below) | 0x010401ff |
|
||||
| `char[value_len] sys_toolchain` | Toolchain Name | "GNU GCC" |
|
||||
| `char[value_len] sys_toolchain_ver` | Toolchain Version | "6.2.1" |
|
||||
|
||||
@@ -1,98 +0,0 @@
|
||||
# ARK DIST SR
|
||||
|
||||
ARK DIST SR is a low range, open source [DroneCAN](index.md) [distance sensor](../sensor/rangefinders.md).
|
||||
It has an approximate range of between 8cm to 30m.
|
||||
|
||||

|
||||
|
||||
## Where to Buy
|
||||
|
||||
Order this module from:
|
||||
|
||||
- [ARK Electronics](https://arkelectron.com/product/ark-dist-sr/) (US)
|
||||
|
||||
## Hardware Specifications
|
||||
|
||||
- [Open Source Schematic and BOM](https://github.com/ARK-Electronics/ARK_DIST)
|
||||
- Sensors
|
||||
- [Broadcom AFBR-S50LV85D Time-of-Flight Distance Sensor](https://www.broadcom.com/products/optical-sensors/time-of-flight-3d-sensors/afbr-s50lv85d)
|
||||
- Typical distance range up to 30m
|
||||
- Integrated 850 nm laser light source
|
||||
- Field-of-View (FoV) of 12.4° x 6.2° with 32 pixels
|
||||
- Operation of up to 200k Lux ambient light
|
||||
- Reference Pixel for system health monitoring
|
||||
- Works well on all surface conditions
|
||||
- Transmitter beam of 2° x 2° to illuminate between 1 and 3 pixels
|
||||
- Two Pixhawk Standard CAN Connectors (4 Pin JST GH)
|
||||
- Pixhawk Standard UART Connector (6 Pin JST SH)
|
||||
- Pixhawk Standard Debug Connector (6 Pin JST SH)
|
||||
- Small Form Factor
|
||||
- 2.0cm x 2.8cm x 1.4cm
|
||||
- 4g
|
||||
- LED Indicators
|
||||
- USA Built
|
||||
- NDAA Compliant
|
||||
- Power Requirements
|
||||
- 5v
|
||||
- 84mA Average
|
||||
- 86mA Max
|
||||
|
||||
## Hardware Setup
|
||||
|
||||
### Wiring
|
||||
|
||||
The ARK DIST is connected to the CAN bus using a Pixhawk standard 4 pin JST GH cable.
|
||||
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
|
||||
|
||||
The ARK DIST can also be connected with UART and communicates over MAVLink sending the [DISTANCE_SENSOR](https://mavlink.io/en/messages/common.html#DISTANCE_SENSOR) message.
|
||||
|
||||
## Firmware Setup
|
||||
|
||||
ARK DIST SR runs the [PX4 DroneCAN Firmware](px4_cannode_fw.md).
|
||||
As such, it supports firmware update over the CAN bus and [dynamic node allocation](index.md#node-id-allocation).
|
||||
|
||||
## PX4 Configuration
|
||||
|
||||
### DroneCAN
|
||||
|
||||
#### Enable DroneCAN
|
||||
|
||||
The steps are:
|
||||
|
||||
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)) and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
|
||||
- Connect ARK DIST SR CAN to the Pixhawk CAN.
|
||||
|
||||
Once enabled, the module will be detected on boot.
|
||||
Distance sensor data should arrive at 40Hz.
|
||||
|
||||
DroneCAN configuration in PX4 is explained in more detail in [DroneCAN > Enabling DroneCAN](../dronecan/index.md#enabling-dronecan).
|
||||
|
||||
#### CAN Configuration
|
||||
|
||||
First set the parameters to [Enable DroneCAN](#enable-dronecan) (as shown above).
|
||||
|
||||
Set the following parameters in _QGroundControl_:
|
||||
|
||||
- Enable [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to 2 for dynamic node allocation.
|
||||
- Enable [UAVCAN_SUB_RNG](../advanced_config/parameter_reference.md#UAVCAN_SUB_RNG).
|
||||
- Set [EKF2_RNG_A_HMAX](../advanced_config/parameter_reference.md#EKF2_RNG_A_HMAX) to `30`.
|
||||
- Set [EKF2_RNG_QLTY_T](../advanced_config/parameter_reference.md#EKF2_RNG_QLTY_T) to `0.2`.
|
||||
- Set [UAVCAN_RNG_MIN](../advanced_config/parameter_reference.md#UAVCAN_RNG_MIN) to `0.08`.
|
||||
- Set [UAVCAN_RNG_MAX](../advanced_config/parameter_reference.md#UAVCAN_RNG_MAX) to `30`.
|
||||
|
||||
See also [Distance Sensor/Range Finder in _DroneCAN > Subscriptions and Publications_](../dronecan/#distance-sensor-range-finder).
|
||||
|
||||
### UART/MAVLink Configuration
|
||||
|
||||
If connecting via a UART set the following parameters in _QGroundControl_:
|
||||
|
||||
- Set [MAV_X_CONFIG](../advanced_config/parameter_reference.md#MAV_0_CONFIG) to the port the sensor is connected to.
|
||||
- Set [MAV_X_FORWARD](../advanced_config/parameter_reference.md#MAV_0_FORWARD) to `0` (off).
|
||||
- Set [MAV_X_MODE](../advanced_config/parameter_reference.md#MAV_0_MODE) to `7` or `13` to (Minimal or Low Bandwidth) to reduce memory usage.
|
||||
- Set `SER_XXX_BAUD` to `115200`, where `XXX` is specific to the port you are using (such as [SER_GPS2_BAUD](../advanced_config/parameter_reference.md#SER_GPS2_BAUD)).
|
||||
- Set [EKF2_RNG_A_HMAX](../advanced_config/parameter_reference.md#EKF2_RNG_A_HMAX) to `30`.
|
||||
- Set [EKF2_RNG_QLTY_T](../advanced_config/parameter_reference.md#EKF2_RNG_QLTY_T) to `0.2`.
|
||||
|
||||
## See Also
|
||||
|
||||
- [ARK DIST SR](https://docs.arkelectron.com/sensor/ark-dist) (ARK Docs)
|
||||
@@ -1,97 +0,0 @@
|
||||
# ARK DIST MR
|
||||
|
||||
ARK DIST MR is a mid range, open source [DroneCAN](index.md) [distance sensor](../sensor/rangefinders.md).
|
||||
|
||||

|
||||
|
||||
## Where to Buy
|
||||
|
||||
Order this module from:
|
||||
|
||||
- [ARK Electronics](https://arkelectron.com/product/ark-dist-mr/) (US)
|
||||
|
||||
## Hardware Specifications
|
||||
|
||||
- [Open Source Schematic and BOM](https://github.com/ARK-Electronics/ARK_DIST)
|
||||
- Sensors
|
||||
- [Broadcom AFBR-S50LX85D Time-of-Flight Distance Sensor](https://www.broadcom.com/products/optical-sensors/time-of-flight-3d-sensors/afbr-s50lx85d)
|
||||
- Typical distance range up to 50m
|
||||
- Integrated 850 nm laser light source
|
||||
- Field-of-View (FoV) of 12.4° x 6.2° with 32 pixels
|
||||
- Operation of up to 200k Lux ambient light
|
||||
- Reference Pixel for system health monitoring
|
||||
- Works well on all surface conditions
|
||||
- Transmitter beam of 2° x 2° to illuminate between 1 and 3 pixels
|
||||
- Two Pixhawk Standard CAN Connectors (4 Pin JST GH)
|
||||
- Pixhawk Standard UART Connector (6 Pin JST SH)
|
||||
- Pixhawk Standard Debug Connector (6 Pin JST SH)
|
||||
- Small Form Factor
|
||||
- 2.0cm x 2.8cm x 1.4cm
|
||||
- 4g
|
||||
- LED Indicators
|
||||
- USA Built
|
||||
- NDAA Compliant
|
||||
- Power Requirements
|
||||
- 5v
|
||||
- 78mA Average
|
||||
- 84mA Max
|
||||
|
||||
## Hardware Setup
|
||||
|
||||
### Wiring
|
||||
|
||||
The ARK DIST is connected to the CAN bus using a Pixhawk standard 4 pin JST GH cable.
|
||||
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
|
||||
|
||||
The ARK DIST can also be connected with UART and communicates over MAVLink sending the [DISTANCE_SENSOR](https://mavlink.io/en/messages/common.html#DISTANCE_SENSOR) message.
|
||||
|
||||
## Firmware Setup
|
||||
|
||||
ARK DIST MR runs the [PX4 DroneCAN Firmware](px4_cannode_fw.md).
|
||||
As such, it supports firmware update over the CAN bus and [dynamic node allocation](index.md#node-id-allocation).
|
||||
|
||||
## PX4 Configuration
|
||||
|
||||
### DroneCAN
|
||||
|
||||
#### Enable DroneCAN
|
||||
|
||||
The steps are:
|
||||
|
||||
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)) and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
|
||||
- Connect ARK DIST SR CAN to the Pixhawk CAN.
|
||||
|
||||
Once enabled, the module will be detected on boot.
|
||||
Distance sensor data should arrive at 40Hz.
|
||||
|
||||
DroneCAN configuration in PX4 is explained in more detail in [DroneCAN > Enabling DroneCAN](../dronecan/index.md#enabling-dronecan).
|
||||
|
||||
#### CAN Configuration
|
||||
|
||||
First set the parameters to [Enable DroneCAN](#enable-dronecan) (as shown above).
|
||||
|
||||
Set the following parameters in _QGroundControl_:
|
||||
|
||||
- Enable [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to 2 for dynamic node allocation.
|
||||
- Enable [UAVCAN_SUB_RNG](../advanced_config/parameter_reference.md#UAVCAN_SUB_RNG).
|
||||
- Set [EKF2_RNG_A_HMAX](../advanced_config/parameter_reference.md#EKF2_RNG_A_HMAX) to `50`.
|
||||
- Set [EKF2_RNG_QLTY_T](../advanced_config/parameter_reference.md#EKF2_RNG_QLTY_T) to `0.2`.
|
||||
- Set [UAVCAN_RNG_MIN](../advanced_config/parameter_reference.md#UAVCAN_RNG_MIN) to `0.08`.
|
||||
- Set [UAVCAN_RNG_MAX](../advanced_config/parameter_reference.md#UAVCAN_RNG_MAX) to `50`.
|
||||
|
||||
See also [Distance Sensor/Range Finder in _DroneCAN > Subscriptions and Publications_](../dronecan/#distance-sensor-range-finder).
|
||||
|
||||
### UART/MAVLink Configuration
|
||||
|
||||
If connecting via a UART set the following parameters in _QGroundControl_:
|
||||
|
||||
- Set [MAV_X_CONFIG](../advanced_config/parameter_reference.md#MAV_0_CONFIG) to the port the sensor is connected to.
|
||||
- Set [MAV_X_FORWARD](../advanced_config/parameter_reference.md#MAV_0_FORWARD) to `0` (off).
|
||||
- Set [MAV_X_MODE](../advanced_config/parameter_reference.md#MAV_0_MODE) to `7` or `13` to (Minimal or Low Bandwidth) to reduce memory usage.
|
||||
- Set `SER_XXX_BAUD` to `115200`, where `XXX` is specific to the port you are using (such as [SER_GPS2_BAUD](../advanced_config/parameter_reference.md#SER_GPS2_BAUD)).
|
||||
- Set [EKF2_RNG_A_HMAX](../advanced_config/parameter_reference.md#EKF2_RNG_A_HMAX) to `50`.
|
||||
- Set [EKF2_RNG_QLTY_T](../advanced_config/parameter_reference.md#EKF2_RNG_QLTY_T) to `0.2`.
|
||||
|
||||
## See Also
|
||||
|
||||
- [ARK DIST MR](https://docs.arkelectron.com/sensor/ark-dist) (ARK Docs)
|
||||
@@ -20,7 +20,6 @@ Order this module from:
|
||||
- Multi-band RTK with fast convergence times and reliable performance
|
||||
- High update rate for highly dynamic applications
|
||||
- Centimetre accuracy in a small and energy efficient module
|
||||
- Moving Base for Heading
|
||||
- Bosch BMM150 Magnetometer
|
||||
- Bosch BMP388 Barometer
|
||||
- Invensense ICM-42688-P 6-Axis IMU
|
||||
|
||||
@@ -1,163 +0,0 @@
|
||||
# ARK RTK GPS L1 L5
|
||||
|
||||
[ARK RTK GPS L1 L5](https://arkelectron.gitbook.io/ark-documentation/sensors/ark-rtk-gps) is an open source [DroneCAN](index.md) [RTK GPS](../gps_compass/rtk_gps.md), [u-blox F9P](https://www.u-blox.com/en/product/zed-f9p-module), magnetometer, barometer, IMU, buzzer, and safety switch module.
|
||||
|
||||

|
||||
|
||||
## Where to Buy
|
||||
|
||||
Order this module from:
|
||||
|
||||
- [ARK Electronics](https://arkelectron.com/product/ark-rtk-gps-l1-l5/) (US)
|
||||
|
||||
## Hardware Specifications
|
||||
|
||||
- [Open Source Schematic and BOM](https://github.com/ARK-Electronics/ARK_RTK_GPS)
|
||||
- Sensors
|
||||
- Ublox F9P GPS
|
||||
- Multi-band GNSS receiver delivers centimetre level accuracy in seconds
|
||||
- Concurrent reception of GPS, GLONASS, Galileo and BeiDou
|
||||
- Multi-band RTK with fast convergence times and reliable performance
|
||||
- High update rate for highly dynamic applications
|
||||
- Centimetre accuracy in a small and energy efficient module
|
||||
- Does not Support Moving Base for Heading
|
||||
- Bosch BMM150 Magnetometer
|
||||
- Bosch BMP388 Barometer
|
||||
- Invensense ICM-42688-P 6-Axis IMU
|
||||
- STM32F412CEU6 MCU
|
||||
- Safety Button
|
||||
- Buzzer
|
||||
- Two Pixhawk Standard CAN Connectors (4 Pin JST GH)
|
||||
- F9P `UART 2` Connector
|
||||
- 3 Pin JST GH
|
||||
- TX, RX, GND
|
||||
- Pixhawk Standard Debug Connector (6 Pin JST SH)
|
||||
- LED Indicators
|
||||
- Safety LED
|
||||
- GPS Fix
|
||||
- RTK Status
|
||||
- RGB system status
|
||||
- USA Built
|
||||
- Power Requirements
|
||||
- 5V
|
||||
- 170mA Average
|
||||
- 180mA Max
|
||||
|
||||
## Hardware Setup
|
||||
|
||||
### Wiring
|
||||
|
||||
The ARK RTK GPS L1 L5 is connected to the CAN bus using a Pixhawk standard 4 pin JST GH cable. For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
|
||||
|
||||
### Mounting
|
||||
|
||||
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
|
||||
|
||||
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 configuration](#px4-configuration).
|
||||
|
||||
## Firmware Setup
|
||||
|
||||
ARK RTK GPS L1 L5 runs the [PX4 cannode firmware](px4_cannode_fw.md). As such, it supports firmware update over the CAN bus and [dynamic node allocation](index.md#node-id-allocation).
|
||||
|
||||
ARK RTK GPS L1 L5 boards ship with recent firmware pre-installed, but if you want to build and flash the latest firmware yourself, refer to the [cannode firmware build instructions](px4_cannode_fw.md#building-the-firmware).
|
||||
|
||||
Firmware target: `ark_can-rtk-gps_default`
|
||||
Bootloader target: `ark_can-rtk-gps_canbootloader`
|
||||
|
||||
## Flight Controller Setup
|
||||
|
||||
### Enabling DroneCAN
|
||||
|
||||
In order to use the ARK RTK GPS L1 L5, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
|
||||
|
||||
The steps are:
|
||||
|
||||
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
|
||||
- Connect ARK RTK GPS L1 L5 CAN to the Pixhawk CAN.
|
||||
|
||||
Once enabled, the module will be detected on boot.
|
||||
GPS data should arrive at 10Hz.
|
||||
|
||||
### PX4 Configuration
|
||||
|
||||
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
|
||||
|
||||
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
|
||||
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
|
||||
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
|
||||
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS L1 L5 from the vehicles centre of gravity.
|
||||
|
||||
### ARK RTK GPS L1 L5 Configuration
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS L1 L5 itself:
|
||||
|
||||
| Parameter | Description |
|
||||
| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |
|
||||
|
||||
### Setting Up Rover and Fixed Base
|
||||
|
||||
Position of the rover is established using RTCM messages from the RTK base module (the base module is connected to QGC, which sends the RTCM information to PX4 via MAVLink).
|
||||
|
||||
PX4 DroneCAN parameters:
|
||||
|
||||
- [UAVCAN_PUB_RTCM](../advanced_config/parameter_reference.md#UAVCAN_PUB_RTCM):
|
||||
- Makes PX4 publish RTCM messages ([RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream)) to the bus (which it gets from the RTK base module via QGC).
|
||||
|
||||
Rover module parameters (also [set using QGC](../dronecan/index.md#qgc-cannode-parameter-configuration)):
|
||||
|
||||
- [CANNODE_SUB_RTCM](../advanced_config/parameter_reference.md#CANNODE_SUB_RTCM) tells the rover that it should subscribe to [RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream) RTCM messages on the bus (from the moving base).
|
||||
|
||||
::: info
|
||||
Use [UAVCAN_PUB_MBD](../advanced_config/parameter_reference.md#UAVCAN_PUB_MBD) and [CANNODE_SUB_MBD](../advanced_config/parameter_reference.md#CANNODE_SUB_MBD) instead if you want to implement moving base (see below) at the same time.
|
||||
:::
|
||||
|
||||
For more information see [Rover and Fixed Base](../dronecan/index.md#rover-and-fixed-base) in the DroneCAN guide.
|
||||
|
||||
## LED Meanings
|
||||
|
||||
- The GPS status lights are located to the right of the connectors
|
||||
- Blinking green is GPS fix
|
||||
- Blinking blue is received corrections and RTK Float
|
||||
- Solid blue is RTK Fixed
|
||||
|
||||
- The CAN status lights are located top the left of the connectors
|
||||
- Slow blinking green is waiting for CAN connection
|
||||
- Fast blinking green is normal operation
|
||||
- Slow blinking green and blue is CAN enumeration
|
||||
- Fast blinking blue and red is firmware update in progress
|
||||
- Blinking red is error
|
||||
- If you see a red LED there is an error and you should check the following
|
||||
- Make sure the flight controller has an SD card installed
|
||||
- Make sure the ARK RTK GPS L1 L5 has `ark_can-rtk-gps_canbootloader` installed prior to flashing `ark_can-rtk-gps_default`
|
||||
- Remove binaries from the root and ufw directories of the SD card and try to build and flash again
|
||||
|
||||
### Updating Ublox F9P Module
|
||||
|
||||
ARK RTK GPS L1 L5 comes with the Ublox F9P module up to date with version 1.13 or newer. However, you can check the version and update the firmware if desired.
|
||||
|
||||
The steps are:
|
||||
|
||||
1. [Download u-center from u-blox.com](https://www.u-blox.com/en/product/u-center) and install on your PC (Windows only)
|
||||
2. Open the [u-blox ZED-F9P website](https://www.u-blox.com/en/product/zed-f9p-module#tab-documentation-resources)
|
||||
3. Scroll down and click on the "Show Legacy Documents" box
|
||||
4. Scroll down again to Firmware Update and download your desired firmware (at least version 1.13 is needed)
|
||||
5. While holding down the safety switch on the ARK RTK GPS L1 L5, connect it to power via one of its CAN ports and hold until all 3 LEDs blink rapidly
|
||||
6. Connect the ARK RTK GPS L1 L5 to your PC via its debug port with a cable such as the Black Magic Probe or an FTDI
|
||||
7. Open u-center, select the COM port for the ARK RTK GPS L1 L5 and connect
|
||||

|
||||
8. Check the current firmware version by selecting View, Messages View, UBX, MON, VER
|
||||

|
||||
9. To update the firmware:
|
||||
1. Select Tools, Firmware Update
|
||||
2. The Firmware image field should be the .bin file downloaded from the u-blox ZED-F9P website
|
||||
3. Check the "Use this baudrate for update" checkbox and select 115200 from the drop-down
|
||||
4. Ensure the other checkboxes are as shown below
|
||||
5. Push the green GO button on the bottom left
|
||||
6. "Firmware Update SUCCESS" should be displayed if it updated successfully
|
||||

|
||||
|
||||
## See Also
|
||||
|
||||
- [ARK RTK GPS L1 L5 Documentation](https://arkelectron.gitbook.io/ark-documentation/sensors/ark-rtk-gps) (ARK Docs)
|
||||
@@ -1,141 +0,0 @@
|
||||
# ARK X20 RTK GPS
|
||||
|
||||
[ARK X20 RTK GPS](https://docs.arkelectron.com/gps/ark-x20-rtk-gps) is an open source [DroneCAN](index.md) [RTK GPS](../gps_compass/rtk_gps.md), [u-blox ZED-X20P all-band high precision GNSS module](https://www.u-blox.com/en/product/zed-x20p-module), magnetometer, barometer, IMU, buzzer, and safety switch module.
|
||||
|
||||

|
||||
|
||||
## Where to Buy
|
||||
|
||||
Order this module from:
|
||||
|
||||
- [ARK Electronics](https://arkelectron.com/product/ark-x20-rtk-gps/) (US)
|
||||
|
||||
## Hardware Specifications
|
||||
|
||||
- [Open Source Schematic and BOM](https://github.com/ARK-Electronics/ARK_RTK_GPS)
|
||||
- Sensors
|
||||
- Ublox ZED-X20P
|
||||
- All-band all constellation GNSS receiver
|
||||
- Best position accuracy and availability in different environments
|
||||
- RTK, PPP-RTK and PPP algorithms expanding the limits of performance
|
||||
- Highest quality GNSS raw data
|
||||
- u-blox end-to-end hardened security
|
||||
- 25Hz update rate
|
||||
- ST IIS2MDC Magnetometer
|
||||
- Bosch BMP390 Barometer
|
||||
- Invensense ICM-42688-P 6-Axis IMU
|
||||
- STM32F412VGH6 MCU
|
||||
- Safety Button
|
||||
- Buzzer
|
||||
- Two Pixhawk Standard CAN Connectors (4 Pin JST GH)
|
||||
- X20 “UART 2” Connector
|
||||
- 4 Pin JST GH
|
||||
- TX, RX, PPS, GND
|
||||
- I2C Expansion Connector
|
||||
- 4 Pin JST-GH
|
||||
- 5.0V, SCL, SDA, GND
|
||||
- Pixhawk Standard Debug Connector (6 Pin JST SH)
|
||||
- LED Indicators
|
||||
- Safety LED
|
||||
- GPS Fix
|
||||
- RTK Status
|
||||
- RGB system status
|
||||
- USA Built
|
||||
- Power Requirements
|
||||
- 5V
|
||||
- 144mA Average
|
||||
- 157mA Max
|
||||
|
||||
## Hardware Setup
|
||||
|
||||
### Wiring
|
||||
|
||||
The ARK X20 RTK GPS is connected to the CAN bus using a Pixhawk standard 4 pin JST GH cable. For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
|
||||
|
||||
### Mounting
|
||||
|
||||
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
|
||||
|
||||
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 configuration](#px4-configuration).
|
||||
|
||||
## Firmware Setup
|
||||
|
||||
ARK X20 RTK GPS runs the [PX4 cannode firmware](px4_cannode_fw.md). As such, it supports firmware update over the CAN bus and [dynamic node allocation](index.md#node-id-allocation).
|
||||
|
||||
ARK X20 RTK GPS boards ship with recent firmware pre-installed, but if you want to build and flash the latest firmware yourself, refer to the [cannode firmware build instructions](px4_cannode_fw.md#building-the-firmware).
|
||||
|
||||
Firmware target: `ark_can-rtk-gps_default`
|
||||
Bootloader target: `ark_can-rtk-gps_canbootloader`
|
||||
|
||||
## Flight Controller Setup
|
||||
|
||||
### Enabling DroneCAN
|
||||
|
||||
In order to use the ARK X20 RTK GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
|
||||
|
||||
The steps are:
|
||||
|
||||
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
|
||||
- Connect ARK X20 RTK GPS CAN to the Pixhawk CAN.
|
||||
|
||||
Once enabled, the module will be detected on boot.
|
||||
GPS data should arrive at 10Hz.
|
||||
|
||||
### PX4 Configuration
|
||||
|
||||
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
|
||||
|
||||
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
|
||||
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
|
||||
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
|
||||
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK X20 RTK GPS from the vehicles centre of gravity.
|
||||
|
||||
### ARK X20 RTK GPS Configuration
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK X20 RTK GPS itself:
|
||||
|
||||
| Parameter | Description |
|
||||
| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |
|
||||
|
||||
### Setting Up Rover and Fixed Base
|
||||
|
||||
Position of the rover is established using RTCM messages from the RTK base module (the base module is connected to QGC, which sends the RTCM information to PX4 via MAVLink).
|
||||
|
||||
PX4 DroneCAN parameters:
|
||||
|
||||
- [UAVCAN_PUB_RTCM](../advanced_config/parameter_reference.md#UAVCAN_PUB_RTCM):
|
||||
- Makes PX4 publish RTCM messages ([RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream)) to the bus (which it gets from the RTK base module via QGC).
|
||||
|
||||
Rover module parameters (also [set using QGC](../dronecan/index.md#qgc-cannode-parameter-configuration)):
|
||||
|
||||
- [CANNODE_SUB_RTCM](../advanced_config/parameter_reference.md#CANNODE_SUB_RTCM) tells the rover that it should subscribe to [RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream) RTCM messages on the bus (from the moving base).
|
||||
|
||||
::: info
|
||||
Use [UAVCAN_PUB_MBD](../advanced_config/parameter_reference.md#UAVCAN_PUB_MBD) and [CANNODE_SUB_MBD](../advanced_config/parameter_reference.md#CANNODE_SUB_MBD) instead if you want to implement moving base (see below) at the same time.
|
||||
:::
|
||||
|
||||
For more information see [Rover and Fixed Base](../dronecan/index.md#rover-and-fixed-base) in the DroneCAN guide.
|
||||
|
||||
## LED Meanings
|
||||
|
||||
- The GPS status lights are located to the right of the connectors
|
||||
- Blinking green is GPS fix
|
||||
- Blinking blue is received corrections and RTK Float
|
||||
- Solid blue is RTK Fixed
|
||||
|
||||
- The CAN status lights are located top the left of the connectors
|
||||
- Slow blinking green is waiting for CAN connection
|
||||
- Fast blinking green is normal operation
|
||||
- Slow blinking green and blue is CAN enumeration
|
||||
- Fast blinking blue and red is firmware update in progress
|
||||
- Blinking red is error
|
||||
- If you see a red LED there is an error and you should check the following
|
||||
- Make sure the flight controller has an SD card installed
|
||||
- Make sure the ARK X20 RTK GPS has `ark_can-rtk-gps_canbootloader` installed prior to flashing `ark_can-rtk-gps_default`
|
||||
- Remove binaries from the root and ufw directories of the SD card and try to build and flash again
|
||||
|
||||
## See Also
|
||||
|
||||
- [ARK X20 RTK GPS Documentation](https://docs.arkelectron.com/gps/ark-x20-rtk-gps) (ARK Docs)
|
||||
@@ -62,8 +62,6 @@ Supported hardware includes (this is not an exhaustive list):
|
||||
- [Holybro RM3100 Professional Grade Compass](https://holybro.com/products/dronecan-rm3100-compass)
|
||||
- [RaccoonLab RM3100 Magnetometer](https://docs.raccoonlab.co/guide/gps_mag_baro/mag_rm3100.html)
|
||||
- Distance sensors
|
||||
- [ARK Dist](ark_dist.md)
|
||||
- [Ark Dist MR](ark_dist_mr.md)
|
||||
- [ARK Flow](ark_flow.md)
|
||||
- [Ark Flow MR](ark_flow_mr.md)
|
||||
- [Avionics Anonymous Laser Altimeter UAVCAN Interface](../dronecan/avanon_laser_interface.md)
|
||||
|
||||
@@ -1,24 +0,0 @@
|
||||
# Gain compression
|
||||
|
||||
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
|
||||
|
||||
Automatic gain compression reduces the gains of the angular-rate PID whenever oscillations are detected.
|
||||
It monitors the angular-rate controller output through a band-pass filter to identify these oscillations.
|
||||
|
||||
This approach is a safe adaptive mechanism for stable aircraft: the PID gains remain unchanged when no oscillations are present, they are never increased beyond their nominal values, and they are bounded by a minimum limit.
|
||||
|
||||
Gain compression can help prevent actuator damage and even loss of the vehicle in cases such as airspeed-sensor failure (loss of airspeed scaling) or in-flight changes in dynamics (e.g.: CG shifts, inertia changes), or other failures that could cause the angular-rate loop to become oscillatory.
|
||||
|
||||

|
||||
|
||||
## Usage
|
||||
|
||||
Gain compression is enabled by default ([FW_GC_EN](../advanced_config/parameter_reference.md#FW_GC_EN)).
|
||||
|
||||
It should be disabled during fixed wing [manual tuning](../config_fw/pid_tuning_guide_fixedwing.md) to avoid over-tuning.
|
||||
It does not need to be disabled when autotuning.
|
||||
|
||||
## Parameters
|
||||
|
||||
- [FW_GC_EN](../advanced_config/parameter_reference.md#FW_GC_EN)
|
||||
- [FW_GC_GAIN_MIN](../advanced_config/parameter_reference.md#FW_GC_GAIN_MIN)
|
||||
@@ -1,5 +0,0 @@
|
||||
# Fixedwing-Specific Features
|
||||
|
||||
This section lists features that are specific to (or customised for) fixed-wings:
|
||||
|
||||
- [Gain Compression](../features_fw/gain_compression.md)
|
||||
@@ -100,24 +100,6 @@ At very high level, the main differences are:
|
||||
|
||||
<a id="licensing-and-trademarks"></a>
|
||||
|
||||
### FMUv6 Comparison
|
||||
|
||||
| Feature | **FMUv6X-RT** | **FMUv6X** | **FMUv6C** |
|
||||
| ------------------ | --------------------- | ----------------- | ------------------ |
|
||||
| **FMU MCU** | NXP i.MX RT1176 | STM32H753 | STM32H743V |
|
||||
| **RAM** | 2 MB | 1 MB | 1 MB |
|
||||
| **Flash** | 64 MB Octal SPI | 2 MB internal | 2 MB internal |
|
||||
| **IO MCU** | STM32F103 | STM32F103 | STM32F103 |
|
||||
| **Secure Element** | NXP SE051 | NXP SE051 | Not supported |
|
||||
| **PAB Standard** | Supported | Supported | Not supported |
|
||||
| **Ethernet** | Supported | Supported | Not supported |
|
||||
| **IMUs** | 3× | 3× | 2× |
|
||||
| **Barometers** | 2× | 2× | 1× |
|
||||
| **Magnetometer** | 1× | 1× | 1× |
|
||||
| **FMU PWM** | 12× | 8× | 8× |
|
||||
| **IO PWM** | 8× | 8× | 8× |
|
||||
| **CAN Bus** | 3× | 2× | 2× |
|
||||
|
||||
### Licensing and Trademarks
|
||||
|
||||
Pixhawk project schematics and reference designs are licensed under [CC BY-SA 3](https://creativecommons.org/licenses/by-sa/3.0/legalcode).
|
||||
|
||||
@@ -1,62 +0,0 @@
|
||||
# ARK DAN GPS
|
||||
|
||||
[ARK DAN GPS](https://arkelectron.gitbook.io/ark-documentation/gps/ark-dan-gps) is a made in the USA and NDAA-compliant [GNSS/GPS](../gps_compass/index.md) u-blox DAN-F10N GPS and industrial magnetometer.
|
||||
|
||||

|
||||
|
||||
## Where to Buy
|
||||
|
||||
Order this module from:
|
||||
|
||||
- [ARK Electronics](https://arkelectron.com/product/ark-dan-gps/) (US)
|
||||
|
||||
## Hardware Specifications
|
||||
|
||||
- [Open Source Schematic and BOM](https://github.com/ARK-Electronics/ARK_DAN_GPS)
|
||||
- Sensors
|
||||
- [u-blox DAN-F10N](https://www.u-blox.com/en/product/dan-f10n-module)
|
||||
- L1/L5/E5a/B2a bands
|
||||
- Consistently strong performance regardless of installation
|
||||
- Integrated SAW-LNA-SAW for exceptional out-of-band jamming immunity
|
||||
- u-blox F10 proprietary dual-band multipath mitigation technology
|
||||
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
|
||||
- Pixhawk Standard UART/I2C Connector (6 Pin JST SH)
|
||||
- Power Requirements
|
||||
- 5V
|
||||
- 25mA Average
|
||||
- 44mA Max
|
||||
- LED Indicators
|
||||
- GPS Fix
|
||||
- USA Built
|
||||
- NDAA Compliant
|
||||
- 6 Pin Pixhawk Standard UART/I2C Cable
|
||||
|
||||
## Hardware setup
|
||||
|
||||
The module comes with a Pixhawk-standard 6pin connector that will plug into the `GPS2` port on recent Pixhawk flight controllers.
|
||||
It should be mounted front facing, as far away from the flight controller and other electronics as possible.
|
||||
|
||||
For more information see [Mounting the GNSS/Compass](../gps_compass/index.md#mounting-the-gnss-compass) and [Hardware Setup](../gps_compass/index.md#hardware-setup).
|
||||
|
||||
## PX4 Configuration
|
||||
|
||||
The module should be plug-n-play when used with the `GPS2` port on most flight controllers.
|
||||
|
||||
[Secondary GPS Configuration (UART)](../gps_compass/index.md#secondary-gps-configuration-uart) explains how you can configure the port if the GPS is not detected (note, that the configuration is the same, even if you are using GPS 2 as the primary compass).
|
||||
|
||||
## Pinout
|
||||
|
||||
### Pixhawk Standard UART/I2C Connector - 6 Pin JST-SH
|
||||
|
||||
| Pin Number | Signal Name | Voltage |
|
||||
| ---------- | ----------- | ------- |
|
||||
| 1 | 5V | 5.0V |
|
||||
| 2 | RX | 3.3V |
|
||||
| 3 | TX | 3.3V |
|
||||
| 4 | SCL | 3.3V |
|
||||
| 5 | SDA | 3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
## See Also
|
||||
|
||||
- [ARK DAN GPS Documentation](https://arkelectron.gitbook.io/ark-documentation/gps/ark-dan-gps) (ARK Docs)
|
||||
@@ -1,6 +1,6 @@
|
||||
# ARK SAM GPS
|
||||
|
||||
[ARK SAM GPS](https://arkelectron.gitbook.io/ark-documentation/gps/ark-sam-gps) is a made in the USA and NDAA-compliant [GNSS/GPS](../gps_compass/index.md) u-blox SAM-M10Q GPS and industrial magnetometer.
|
||||
[ARK SAM GPS](https://arkelectron.gitbook.io/ark-documentation/gps/ark-sam-gps>) is a made in the USA and NDAA-compliant [GNSS/GPS](../gps_compass/index.md) u-blox SAM-M10Q GPS and industrial magnetometer.
|
||||
|
||||

|
||||
|
||||
@@ -33,7 +33,7 @@ Order this module from:
|
||||
## Hardware setup
|
||||
|
||||
The module comes with a Pixhawk-standard 6pin connector that will plug into the `GPS2` port on recent Pixhawk flight controllers.
|
||||
It should be mounted front facing, as far away from the flight controller and other electronics as possible.
|
||||
It should be mounted front facing, as far away from the flight controller and other electronics as possible.
|
||||
|
||||
For more information see [Mounting the GNSS/Compass](../gps_compass/index.md#mounting-the-gnss-compass) and [Hardware Setup](../gps_compass/index.md#hardware-setup).
|
||||
|
||||
|
||||
@@ -1,61 +0,0 @@
|
||||
# ARK SAM GPS MINI
|
||||
|
||||
[ARK SAM GPS MINI](https://arkelectron.gitbook.io/ark-documentation/gps/ark-sam-gps) is a made in the USA and NDAA-compliant [GNSS/GPS](../gps_compass/index.md) u-blox SAM-M10Q GPS and industrial magnetometer.
|
||||
|
||||

|
||||
|
||||
## Where to Buy
|
||||
|
||||
Order this module from:
|
||||
|
||||
- [ARK Electronics](https://arkelectron.com/product/ark-sam-gps-mini/) (US)
|
||||
|
||||
## Hardware Specifications
|
||||
|
||||
- [Open Source Schematic and BOM](https://github.com/ARK-Electronics/ARK_SAM_GPS/tree/main)
|
||||
- Sensors
|
||||
- [u-blox SAM-M10Q](https://www.u-blox.com/en/product/sam-m10q-module)
|
||||
- Less than 38 mW power consumption without compromising GNSS performance
|
||||
- Maximum position availability with 4 concurrent GNSS reception
|
||||
- Advanced spoofing and jamming detection
|
||||
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
|
||||
- Pixhawk Standard UART/I2C Connector (6 Pin JST SH)
|
||||
- Power Requirements
|
||||
- 5V
|
||||
- 15mA Average
|
||||
- 20mA Max
|
||||
- LED Indicators
|
||||
- GPS Fix
|
||||
- USA Built
|
||||
- NDAA Compliant
|
||||
- 6 Pin Pixhawk Standard UART/I2C Cable
|
||||
|
||||
## Hardware setup
|
||||
|
||||
The module comes with a Pixhawk-standard 6pin connector that will plug into the `GPS2` port on recent Pixhawk flight controllers.
|
||||
It should be mounted front facing, as far away from the flight controller and other electronics as possible.
|
||||
|
||||
For more information see [Mounting the GNSS/Compass](../gps_compass/index.md#mounting-the-gnss-compass) and [Hardware Setup](../gps_compass/index.md#hardware-setup).
|
||||
|
||||
## PX4 Configuration
|
||||
|
||||
The module should be plug-n-play when used with the `GPS2` port on most flight controllers.
|
||||
|
||||
[Secondary GPS Configuration (UART)](../gps_compass/index.md#secondary-gps-configuration-uart) explains how you can configure the port if the GPS is not detected (note, that the configuration is the same, even if you are using GPS 2 as the primary compass).
|
||||
|
||||
## Pinout
|
||||
|
||||
### Pixhawk Standard UART/I2C Connector - 6 Pin JST-SH
|
||||
|
||||
| Pin Number | Signal Name | Voltage |
|
||||
| ---------- | ----------- | ------- |
|
||||
| 1 | 5V | 5.0V |
|
||||
| 2 | RX | 3.3V |
|
||||
| 3 | TX | 3.3V |
|
||||
| 4 | SCL | 3.3V |
|
||||
| 5 | SDA | 3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
## See Also
|
||||
|
||||
- [ARK SAM GPS MINI Documentation](https://arkelectron.gitbook.io/ark-documentation/gps/ark-sam-gps) (ARK Docs)
|
||||
@@ -25,9 +25,7 @@ These have been tested by the PX4 dev team, or which are popular within the PX4
|
||||
| Device | GPS | Compass | [CAN](../dronecan/index.md) | Buzzer / SafeSw / LED | Notes |
|
||||
| :----------------------------------------------------------- | :---------: | :-----------------------: | :-------------------------: | :-------------------: | :-------------------------- |
|
||||
| [ARK GPS](../dronecan/ark_gps.md) | M9N | BMM150 | ✓ | ✓ | + Baro, IMU |
|
||||
| [ARK DAN GPS](../gps_compass/ark_dan_gps.md) | DAN-F10N | IIS2MDC | | ✓ | |
|
||||
| [ARK SAM GPS](../gps_compass/ark_sam_gps.md) | SAM-M10Q | IIS2MDC | | ✓ | |
|
||||
| [ARK SAM GPS MINI ](../gps_compass/ark_sam_gps_mini.md) | SAM-M10Q | IIS2MDC | | ✓ | |
|
||||
| [ARK TESEO GPS](../dronecan/ark_teseo_gps.md) | Teseo-LIV4F | BMM150 | ✓ | ✓ | + Baro, IMU |
|
||||
| [Avionics Anonymous UAVCAN GNSS/Mag][avionics_anon_can_gnss] | SAM-M8Q | MMC5983MA | ✓ | ✘ | |
|
||||
| [CUAV NEO 3 GPS](../gps_compass/gps_cuav_neo_3.md) | M9N | IST8310 | | ✓ | |
|
||||
@@ -198,14 +196,6 @@ It is possible to have low DOP (good satellite geometry) but still have high EPH
|
||||
|
||||
EPH/EPV values therefore provide a more immediate and practical estimate of the actual GPS accuracy you can expect under current conditions.
|
||||
|
||||
### GNSS Position Fusion
|
||||
|
||||
GNSS position fusion will not begin until yaw alignment is established.
|
||||
If a magnetometer is available, the EKF aligns yaw using the magnetic heading, allowing GPS position fusion to start soon after boot.
|
||||
If no magnetometer is present, the system must rely on GPS yaw (from a dual-antenna setup) or movement-based yaw estimation.
|
||||
Until one of these provides a valid heading, the EKF will not start GPS position fusion, and the vehicle will remain in a “no position” state even though attitude data is valid.
|
||||
This behavior prevents large position errors that could occur when the yaw reference is uncertain.
|
||||
|
||||
## Developer Information
|
||||
|
||||
- GPS/RTK-GPS
|
||||
|
||||
@@ -23,9 +23,7 @@ It also highlights devices that connect via the CAN bus, and those which support
|
||||
| Device | GPS | Compass | [DroneCAN](../dronecan/index.md) | [GPS Yaw](#configuring-gps-as-yaw-heading-source) | PPK |
|
||||
| :-------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------: | :------: | :------------------------------: | :-----------------------------------------------: | :-: |
|
||||
| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P][DualF9P] |
|
||||
| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | |
|
||||
| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna][SeptDualAnt] |
|
||||
| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | BMP390 | ✓ | |
|
||||
| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | ✓ | | |
|
||||
| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P][DualF9P] |
|
||||
| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P][DualF9P] |
|
||||
|
||||
@@ -41,23 +41,6 @@ Key features:
|
||||
|
||||
See [Log Analysis using Flight Review](../log/flight_review.md) for an introduction.
|
||||
|
||||
### Foxglove
|
||||
|
||||
[Foxglove](https://foxglove.dev/) is a purpose-built robotics observation platform that works natively with ULog.
|
||||
It allows you to replay your flights and seek through the timeline to find data of interest.
|
||||
|
||||
Key features:
|
||||
|
||||
- Native support for ULog files — open files by dragging and dropping or using the file dialog.
|
||||
- Multiple visualization panels, including Raw Messages, Plot, 3D, and Map panels.
|
||||
- [PX4 Converter extension](https://github.com/foxglove/px4_converter) that translates selected uORB messages and creates Foxglove schemas for enhanced visualizations.
|
||||
- Save and share custom layouts with panels and their settings.
|
||||
- Cross-platform desktop application (Windows, macOS, Linux).
|
||||
|
||||
See [Foxglove PX4 Docs](https://docs.foxglove.dev/docs/getting-started/frameworks/px4) for more detailed information and instructions.
|
||||
|
||||

|
||||
|
||||
### PlotJuggler
|
||||
|
||||
[PlotJuggler](https://github.com/facontidavide/PlotJuggler) is a desktop application that allows users to easily visualize and analyze data expressed in the form of time series.
|
||||
|
||||
@@ -4,84 +4,75 @@
|
||||
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).
|
||||
|
||||
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) and/or [zenoh](../modules/modules_driver.md#zenoh) 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/transponder_report` | [px4_msgs::msg::TransponderReport](../msg_docs/TransponderReport.md) |
|
||||
| `/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) | 50.0 |
|
||||
| `/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) | 100.0 |
|
||||
| `/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 |
|
||||
| `/fmu/out/wind` | [px4_msgs::msg::Wind](../msg_docs/Wind.md) | 1.0 |
|
||||
| `/fmu/out/gimbal_device_attitude_status` | [px4_msgs::msg::GimbalDeviceAttitudeStatus](../msg_docs/GimbalDeviceAttitudeStatus.md) | 20.0 |
|
||||
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) |
|
||||
| /fmu/in/rover_position_setpoint | [px4_msgs::msg::RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md) |
|
||||
| /fmu/in/rover_speed_setpoint | [px4_msgs::msg::RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md) |
|
||||
| /fmu/in/rover_attitude_setpoint | [px4_msgs::msg::RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md) |
|
||||
| /fmu/in/rover_rate_setpoint | [px4_msgs::msg::RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md) |
|
||||
| /fmu/in/rover_throttle_setpoint | [px4_msgs::msg::RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) |
|
||||
| /fmu/in/rover_steering_setpoint | [px4_msgs::msg::RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) |
|
||||
| /fmu/in/landing_gear | [px4_msgs::msg::LandingGear](../msg_docs/LandingGear.md) |
|
||||
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
|
||||
|
||||
@@ -94,191 +85,192 @@ They are not build into the module, and hence are neither published or subscribe
|
||||
|
||||
::: details See messages
|
||||
|
||||
- [BatteryInfo](../msg_docs/BatteryInfo.md)
|
||||
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
|
||||
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
|
||||
- [Airspeed](../msg_docs/Airspeed.md)
|
||||
- [PpsCapture](../msg_docs/PpsCapture.md)
|
||||
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
|
||||
- [CameraCapture](../msg_docs/CameraCapture.md)
|
||||
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
|
||||
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
|
||||
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
|
||||
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
|
||||
- [AirspeedWind](../msg_docs/AirspeedWind.md)
|
||||
- [OrbTest](../msg_docs/OrbTest.md)
|
||||
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
|
||||
- [GpioOut](../msg_docs/GpioOut.md)
|
||||
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
|
||||
- [Gripper](../msg_docs/Gripper.md)
|
||||
- [VehicleAirData](../msg_docs/VehicleAirData.md)
|
||||
- [TuneControl](../msg_docs/TuneControl.md)
|
||||
- [DebugVect](../msg_docs/DebugVect.md)
|
||||
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
|
||||
- [HomePositionV0](../msg_docs/HomePositionV0.md)
|
||||
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
|
||||
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
|
||||
- [EstimatorBias](../msg_docs/EstimatorBias.md)
|
||||
- [GpioConfig](../msg_docs/GpioConfig.md)
|
||||
- [SystemPower](../msg_docs/SystemPower.md)
|
||||
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
|
||||
- [MissionResult](../msg_docs/MissionResult.md)
|
||||
- [PowerButtonState](../msg_docs/PowerButtonState.md)
|
||||
- [EscStatus](../msg_docs/EscStatus.md)
|
||||
- [HealthReport](../msg_docs/HealthReport.md)
|
||||
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
|
||||
- [SensorGyro](../msg_docs/SensorGyro.md)
|
||||
- [GpioRequest](../msg_docs/GpioRequest.md)
|
||||
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
|
||||
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
|
||||
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
|
||||
- [SensorAirflow](../msg_docs/SensorAirflow.md)
|
||||
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
|
||||
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
|
||||
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
|
||||
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
|
||||
- [ActionRequest](../msg_docs/ActionRequest.md)
|
||||
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
|
||||
- [PwmInput](../msg_docs/PwmInput.md)
|
||||
- [PowerMonitor](../msg_docs/PowerMonitor.md)
|
||||
- [Mission](../msg_docs/Mission.md)
|
||||
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
|
||||
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
|
||||
- [RadioStatus](../msg_docs/RadioStatus.md)
|
||||
- [VehicleRoi](../msg_docs/VehicleRoi.md)
|
||||
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
|
||||
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
|
||||
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
|
||||
- [Rpm](../msg_docs/Rpm.md)
|
||||
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
|
||||
- [Ping](../msg_docs/Ping.md)
|
||||
- [QshellReq](../msg_docs/QshellReq.md)
|
||||
- [SensorMag](../msg_docs/SensorMag.md)
|
||||
- [EstimatorStates](../msg_docs/EstimatorStates.md)
|
||||
- [SensorUwb](../msg_docs/SensorUwb.md)
|
||||
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
|
||||
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
|
||||
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
|
||||
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
|
||||
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
|
||||
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
|
||||
- [AdcReport](../msg_docs/AdcReport.md)
|
||||
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
|
||||
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
|
||||
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
|
||||
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
|
||||
- [SensorCorrection](../msg_docs/SensorCorrection.md)
|
||||
- [UlogStream](../msg_docs/UlogStream.md)
|
||||
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
|
||||
- [GpsInjectData](../msg_docs/GpsInjectData.md)
|
||||
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
|
||||
- [LoggerStatus](../msg_docs/LoggerStatus.md)
|
||||
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
|
||||
- [SensorBaro](../msg_docs/SensorBaro.md)
|
||||
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
|
||||
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
|
||||
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
|
||||
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
|
||||
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
|
||||
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
|
||||
- [DatamanRequest](../msg_docs/DatamanRequest.md)
|
||||
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
|
||||
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
|
||||
- [DatamanResponse](../msg_docs/DatamanResponse.md)
|
||||
- [LedControl](../msg_docs/LedControl.md)
|
||||
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
|
||||
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
|
||||
- [Event](../msg_docs/Event.md)
|
||||
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
|
||||
- [GpioIn](../msg_docs/GpioIn.md)
|
||||
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
|
||||
- [SensorAccel](../msg_docs/SensorAccel.md)
|
||||
- [SensorsStatus](../msg_docs/SensorsStatus.md)
|
||||
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
|
||||
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
|
||||
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
|
||||
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
|
||||
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
|
||||
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
|
||||
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
|
||||
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
|
||||
- [RoverRateStatus](../msg_docs/RoverRateStatus.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)
|
||||
- [Cpuload](../msg_docs/Cpuload.md)
|
||||
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
|
||||
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
|
||||
- [MavlinkLog](../msg_docs/MavlinkLog.md)
|
||||
- [SensorTemp](../msg_docs/SensorTemp.md)
|
||||
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
|
||||
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
|
||||
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
|
||||
- [CellularStatus](../msg_docs/CellularStatus.md)
|
||||
- [QshellRetval](../msg_docs/QshellRetval.md)
|
||||
- [OrbitStatus](../msg_docs/OrbitStatus.md)
|
||||
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
|
||||
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
|
||||
- [LogMessage](../msg_docs/LogMessage.md)
|
||||
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
|
||||
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
|
||||
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
|
||||
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
|
||||
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
|
||||
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
|
||||
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
|
||||
- [NeuralControl](../msg_docs/NeuralControl.md)
|
||||
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
|
||||
- [RcParameterMap](../msg_docs/RcParameterMap.md)
|
||||
- [SensorSelection](../msg_docs/SensorSelection.md)
|
||||
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
|
||||
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
|
||||
- [ActuatorTest](../msg_docs/ActuatorTest.md)
|
||||
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
|
||||
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
|
||||
- [SensorBaro](../msg_docs/SensorBaro.md)
|
||||
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
|
||||
- [MountOrientation](../msg_docs/MountOrientation.md)
|
||||
- [CameraStatus](../msg_docs/CameraStatus.md)
|
||||
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
|
||||
- [FollowTarget](../msg_docs/FollowTarget.md)
|
||||
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
|
||||
- [ButtonEvent](../msg_docs/ButtonEvent.md)
|
||||
- [DebugArray](../msg_docs/DebugArray.md)
|
||||
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
|
||||
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
|
||||
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
|
||||
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
|
||||
- [VehicleImu](../msg_docs/VehicleImu.md)
|
||||
- [GpsDump](../msg_docs/GpsDump.md)
|
||||
- [WheelEncoders](../msg_docs/WheelEncoders.md)
|
||||
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
|
||||
- [DebugValue](../msg_docs/DebugValue.md)
|
||||
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
|
||||
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
|
||||
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
|
||||
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
|
||||
- [RtlStatus](../msg_docs/RtlStatus.md)
|
||||
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
|
||||
- [GimbalControls](../msg_docs/GimbalControls.md)
|
||||
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.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)
|
||||
- [HeaterStatus](../msg_docs/HeaterStatus.md)
|
||||
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
|
||||
- [RcChannels](../msg_docs/RcChannels.md)
|
||||
- [TecsStatus](../msg_docs/TecsStatus.md)
|
||||
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
|
||||
- [InputRc](../msg_docs/InputRc.md)
|
||||
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
|
||||
- [GeofenceResult](../msg_docs/GeofenceResult.md)
|
||||
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
|
||||
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
|
||||
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
|
||||
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
|
||||
- [CameraTrigger](../msg_docs/CameraTrigger.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)
|
||||
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
|
||||
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
|
||||
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
|
||||
- [EventV0](../msg_docs/EventV0.md)
|
||||
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.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)
|
||||
:::
|
||||
|
||||
@@ -503,11 +503,6 @@ publications:
|
||||
- topic: /fmu/out/vehicle_trajectory_waypoint_desired
|
||||
type: px4_msgs::msg::VehicleTrajectoryWaypoint
|
||||
|
||||
- topic: /fmu/out/vehicle_imu
|
||||
type: px4_msgs::msg::VehicleImu
|
||||
rate_limit: 50.
|
||||
instance: 1 # OPTIONAL
|
||||
|
||||
subscriptions:
|
||||
|
||||
- topic: /fmu/in/offboard_control_mode
|
||||
@@ -540,9 +535,6 @@ Each (`topic`,`type`) pairs defines:
|
||||
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.
|
||||
6. **(Optional)**: An additional `instance` field (only for publication entries), which lets you select which instance of a [multi-instance topic](./uorb.md#multi-instance) you want to be published to ROS 2.
|
||||
If provided, this option changes the ROS 2 topic name of the advertised uORB topic appending the instance number: `fmu/out/[uorb topic name][instance]` (plus eventual namespace and message version).
|
||||
In the example above the final topic name would be `/fmu/out/vehicle_imu1`.
|
||||
|
||||
`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.
|
||||
|
||||
@@ -434,7 +434,6 @@ The [complete example code](https://github.com/PX4/PX4-Autopilot/blob/main/src/e
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <unistd.h>
|
||||
|
||||
@@ -2,7 +2,6 @@
|
||||
|
||||
Subcategories:
|
||||
|
||||
- [Adc](modules_driver_adc.md)
|
||||
- [Airspeed Sensor](modules_driver_airspeed_sensor.md)
|
||||
- [Baro](modules_driver_baro.md)
|
||||
- [Camera](modules_driver_camera.md)
|
||||
@@ -47,6 +46,66 @@ MCP23009 <command> [arguments...]
|
||||
status print status info
|
||||
```
|
||||
|
||||
## adc
|
||||
|
||||
Source: [drivers/adc/board_adc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/adc/board_adc)
|
||||
|
||||
### Description
|
||||
|
||||
ADC driver.
|
||||
|
||||
### Usage {#adc_usage}
|
||||
|
||||
```
|
||||
adc <command> [arguments...]
|
||||
Commands:
|
||||
start
|
||||
|
||||
test
|
||||
[-n] Do not publish ADC report, only system power
|
||||
|
||||
stop
|
||||
|
||||
status print status info
|
||||
```
|
||||
|
||||
## ads1115
|
||||
|
||||
Source: [drivers/adc/ads1115](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/adc/ads1115)
|
||||
|
||||
### Description
|
||||
|
||||
Driver to enable an external [ADS1115](https://www.adafruit.com/product/1085) ADC connected via I2C.
|
||||
|
||||
The driver is included by default in firmware for boards that do not have an internal analog to digital converter,
|
||||
such as [PilotPi](../flight_controller/raspberry_pi_pilotpi.md) or [CUAV Nora](../flight_controller/cuav_nora.md)
|
||||
(search for `CONFIG_DRIVERS_ADC_ADS1115` in board configuration files).
|
||||
|
||||
It is enabled/disabled using the
|
||||
[ADC_ADS1115_EN](../advanced_config/parameter_reference.md#ADC_ADS1115_EN)
|
||||
parameter, and is disabled by default.
|
||||
If enabled, internal ADCs are not used.
|
||||
|
||||
### Usage {#ads1115_usage}
|
||||
|
||||
```
|
||||
ads1115 <command> [arguments...]
|
||||
Commands:
|
||||
start
|
||||
[-I] Internal I2C bus(es)
|
||||
[-X] External I2C bus(es)
|
||||
[-b <val>] board-specific bus (default=all) (external SPI: n-th bus
|
||||
(default=1))
|
||||
[-f <val>] bus frequency in kHz
|
||||
[-q] quiet startup (no message if no device found)
|
||||
[-a <val>] I2C address
|
||||
default: 72
|
||||
|
||||
stop
|
||||
|
||||
status print status info
|
||||
```
|
||||
|
||||
## atxxxx
|
||||
|
||||
Source: [drivers/osd/atxxxx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/osd/atxxxx)
|
||||
@@ -749,30 +808,6 @@ lsm303agr <command> [arguments...]
|
||||
status print status info
|
||||
```
|
||||
|
||||
## mcp9808
|
||||
|
||||
Source: [drivers/temperature_sensor/mcp9808](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/temperature_sensor/mcp9808)
|
||||
|
||||
### Usage {#mcp9808_usage}
|
||||
|
||||
```
|
||||
mcp9808 <command> [arguments...]
|
||||
Commands:
|
||||
start
|
||||
[-I] Internal I2C bus(es)
|
||||
[-X] External I2C bus(es)
|
||||
[-b <val>] board-specific bus (default=all) (external SPI: n-th bus
|
||||
(default=1))
|
||||
[-f <val>] bus frequency in kHz
|
||||
[-q] quiet startup (no message if no device found)
|
||||
[-a <val>] I2C address
|
||||
default: 24
|
||||
|
||||
stop
|
||||
|
||||
status print status info
|
||||
```
|
||||
|
||||
## msp_osd
|
||||
|
||||
Source: [drivers/osd/msp_osd](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/osd/msp_osd)
|
||||
|
||||
@@ -1,107 +0,0 @@
|
||||
# Modules Reference: Adc (Driver)
|
||||
|
||||
## TLA2528
|
||||
|
||||
Source: [drivers/adc/tla2528](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/adc/tla2528)
|
||||
|
||||
### Usage {#TLA2528_usage}
|
||||
|
||||
```
|
||||
TLA2528 <command> [arguments...]
|
||||
Commands:
|
||||
start
|
||||
[-I] Internal I2C bus(es)
|
||||
[-X] External I2C bus(es)
|
||||
[-b <val>] board-specific bus (default=all) (external SPI: n-th bus
|
||||
(default=1))
|
||||
[-f <val>] bus frequency in kHz
|
||||
[-q] quiet startup (no message if no device found)
|
||||
|
||||
stop
|
||||
|
||||
status print status info
|
||||
```
|
||||
|
||||
## adc
|
||||
|
||||
Source: [drivers/adc/board_adc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/adc/board_adc)
|
||||
|
||||
### Description
|
||||
|
||||
ADC driver.
|
||||
|
||||
### Usage {#adc_usage}
|
||||
|
||||
```
|
||||
adc <command> [arguments...]
|
||||
Commands:
|
||||
start
|
||||
|
||||
test
|
||||
[-n] Do not publish ADC report, only system power
|
||||
|
||||
stop
|
||||
|
||||
status print status info
|
||||
```
|
||||
|
||||
## ads1115
|
||||
|
||||
Source: [drivers/adc/ads1115](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/adc/ads1115)
|
||||
|
||||
### Description
|
||||
|
||||
Driver to enable an external [ADS1115](https://www.adafruit.com/product/1085) ADC connected via I2C.
|
||||
|
||||
The driver is included by default in firmware for boards that do not have an internal analog to digital converter,
|
||||
such as [PilotPi](../flight_controller/raspberry_pi_pilotpi.md) or [CUAV Nora](../flight_controller/cuav_nora.md)
|
||||
(search for `CONFIG_DRIVERS_ADC_ADS1115` in board configuration files).
|
||||
|
||||
It is enabled/disabled using the
|
||||
[ADC_ADS1115_EN](../advanced_config/parameter_reference.md#ADC_ADS1115_EN)
|
||||
parameter, and is disabled by default.
|
||||
If enabled, internal ADCs are not used.
|
||||
|
||||
### Usage {#ads1115_usage}
|
||||
|
||||
```
|
||||
ads1115 <command> [arguments...]
|
||||
Commands:
|
||||
start
|
||||
[-I] Internal I2C bus(es)
|
||||
[-X] External I2C bus(es)
|
||||
[-b <val>] board-specific bus (default=all) (external SPI: n-th bus
|
||||
(default=1))
|
||||
[-f <val>] bus frequency in kHz
|
||||
[-q] quiet startup (no message if no device found)
|
||||
[-a <val>] I2C address
|
||||
default: 72
|
||||
|
||||
stop
|
||||
|
||||
status print status info
|
||||
```
|
||||
|
||||
## ads7953
|
||||
|
||||
Source: [drivers/adc/ads7953](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/adc/ads7953)
|
||||
|
||||
### Usage {#ads7953_usage}
|
||||
|
||||
```
|
||||
ads7953 <command> [arguments...]
|
||||
Commands:
|
||||
start
|
||||
[-s] Internal SPI bus(es)
|
||||
[-S] External SPI bus(es)
|
||||
[-b <val>] board-specific bus (default=all) (external SPI: n-th bus
|
||||
(default=1))
|
||||
[-c <val>] chip-select pin (for internal SPI) or index (for external SPI)
|
||||
[-m <val>] SPI mode
|
||||
[-f <val>] bus frequency in kHz
|
||||
[-q] quiet startup (no message if no device found)
|
||||
|
||||
stop
|
||||
|
||||
status print status info
|
||||
```
|
||||
@@ -4,10 +4,11 @@
|
||||
|
||||
Source: [drivers/rc/crsf_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/crsf_rc)
|
||||
|
||||
### Description
|
||||
|
||||
### Description
|
||||
This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data
|
||||
|
||||
|
||||
### Usage {#crsf_rc_usage}
|
||||
|
||||
```
|
||||
@@ -16,10 +17,6 @@ crsf_rc <command> [arguments...]
|
||||
start
|
||||
[-d <val>] RC device
|
||||
values: <file:dev>, default: /dev/ttyS3
|
||||
[-b <val>] RC baudrate
|
||||
default: 420000
|
||||
|
||||
inject Inject frame data bytes (for testing)
|
||||
|
||||
stop
|
||||
|
||||
@@ -30,10 +27,11 @@ crsf_rc <command> [arguments...]
|
||||
|
||||
Source: [drivers/rc/dsm_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/dsm_rc)
|
||||
|
||||
### Description
|
||||
|
||||
### Description
|
||||
This module does Spektrum DSM RC input parsing.
|
||||
|
||||
|
||||
### Usage {#dsm_rc_usage}
|
||||
|
||||
```
|
||||
@@ -54,10 +52,11 @@ dsm_rc <command> [arguments...]
|
||||
|
||||
Source: [drivers/rc/ghst_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/ghst_rc)
|
||||
|
||||
### Description
|
||||
|
||||
### Description
|
||||
This module does Ghost (GHST) RC input parsing.
|
||||
|
||||
|
||||
### Usage {#ghst_rc_usage}
|
||||
|
||||
```
|
||||
@@ -76,10 +75,9 @@ ghst_rc <command> [arguments...]
|
||||
|
||||
Source: [drivers/rc_input](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc_input)
|
||||
|
||||
|
||||
### Description
|
||||
|
||||
This module does the RC input parsing and auto-selecting the method. Supported methods are:
|
||||
|
||||
- PPM
|
||||
- SBUS
|
||||
- DSM
|
||||
@@ -87,6 +85,7 @@ This module does the RC input parsing and auto-selecting the method. Supported m
|
||||
- ST24
|
||||
- TBS Crossfire (CRSF)
|
||||
|
||||
|
||||
### Usage {#rc_input_usage}
|
||||
|
||||
```
|
||||
@@ -107,10 +106,11 @@ rc_input <command> [arguments...]
|
||||
|
||||
Source: [drivers/rc/sbus_rc](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/rc/sbus_rc)
|
||||
|
||||
### Description
|
||||
|
||||
### Description
|
||||
This module does SBUS RC input parsing.
|
||||
|
||||
|
||||
### Usage {#sbus_rc_usage}
|
||||
|
||||
```
|
||||
|
||||
@@ -1,21 +1,15 @@
|
||||
# AdcReport (UORB message)
|
||||
|
||||
ADC raw data.
|
||||
|
||||
Communicates raw data from an analog-to-digital converter (ADC) to other modules, such as battery status.
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AdcReport.msg)
|
||||
|
||||
```c
|
||||
# ADC raw data.
|
||||
#
|
||||
# Communicates raw data from an analog-to-digital converter (ADC) to other modules, such as battery status.
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint32 device_id # [-] unique device ID for the sensor that does not change between power cycles
|
||||
int16[16] channel_id # [-] ADC channel IDs, negative for non-existent, TODO: should be kept same as array index
|
||||
int32[16] raw_data # [-] ADC channel raw value, accept negative value, valid if channel ID is positive
|
||||
uint32 resolution # [-] ADC channel resolution
|
||||
float32 v_ref # [V] ADC channel voltage reference, use to calculate LSB voltage(lsb=scale/resolution)
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint32 device_id # unique device ID for the sensor that does not change between power cycles
|
||||
int16[12] channel_id # ADC channel IDs, negative for non-existent, TODO: should be kept same as array index
|
||||
int32[12] raw_data # ADC channel raw value, accept negative value, valid if channel ID is positive
|
||||
uint32 resolution # ADC channel resolution
|
||||
float32 v_ref # ADC channel voltage reference, use to calculate LSB voltage(lsb=scale/resolution)
|
||||
|
||||
```
|
||||
|
||||
@@ -1,5 +1,7 @@
|
||||
# EscReport (UORB message)
|
||||
|
||||
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EscReport.msg)
|
||||
|
||||
```c
|
||||
@@ -16,19 +18,6 @@ uint8 esc_state # State of ESC - depend on Vendor
|
||||
|
||||
uint8 actuator_function # actuator output function (one of Motor1...MotorN)
|
||||
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR2 = 102
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR3 = 103
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR4 = 104
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR5 = 105
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR6 = 106
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR7 = 107
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR8 = 108
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR9 = 109
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR10 = 110
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR11 = 111
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR12 = 112
|
||||
|
||||
uint16 failures # Bitmask to indicate the internal ESC faults
|
||||
int8 esc_power # Applied power 0-100 in % (negative values reserved)
|
||||
|
||||
|
||||
@@ -1,5 +1,7 @@
|
||||
# InputRc (UORB message)
|
||||
|
||||
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InputRc.msg)
|
||||
|
||||
```c
|
||||
@@ -37,13 +39,11 @@ bool rc_lost # RC receiver connection status: True,if no frame has arrived in
|
||||
uint16 rc_lost_frame_count # Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike functionality.
|
||||
uint16 rc_total_frame_count # Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike functionality.
|
||||
uint16 rc_ppm_frame_length # Length of a single PPM frame. Zero for non-PPM systems
|
||||
uint16 rc_frame_rate # RC frame rate in msg/second. 0 = invalid
|
||||
|
||||
uint8 input_source # Input source
|
||||
uint16[18] values # measured pulse widths for each of the supported channels
|
||||
|
||||
int8 link_quality # link quality. Percentage 0-100%. -1 = invalid
|
||||
float32 rssi_dbm # Actual rssi in units of dBm. NaN = invalid
|
||||
int8 link_snr # link signal to noise ratio in units of dB. -1 = invalid
|
||||
|
||||
```
|
||||
|
||||
@@ -27,7 +27,7 @@ uint8 arm_switch # arm/disarm switch: _DISARMED_, ARMED
|
||||
uint8 return_switch # return to launch 2 position switch (mandatory): _NORMAL_, RTL
|
||||
uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER
|
||||
uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD
|
||||
uint8 kill_switch # throttle kill: _NORMAL_, KILL
|
||||
uint8 emergency_stop_switch # throttle kill: _NORMAL_, KILL
|
||||
uint8 termination_switch # trigger termination which cannot be undone
|
||||
uint8 gear_switch # landing gear switch: _DOWN_, UP
|
||||
uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGHT
|
||||
|
||||
@@ -0,0 +1,15 @@
|
||||
# RoverVelocitySetpoint (UORB message)
|
||||
|
||||
Rover Velocity Setpoint
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocitySetpoint.msg)
|
||||
|
||||
```c
|
||||
# Rover Velocity Setpoint
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
float32 speed # [m/s] [@range -inf (Backwards), inf (Forwards)] Speed setpoint
|
||||
float32 bearing # [rad] [@range -pi,pi] [@frame NED] [@invalid: NaN, speed is defined in body x direction] Bearing setpoint
|
||||
float32 yaw # [rad] [@range -pi, pi] [@frame NED] [@invalid NaN, Defaults to vehicle yaw] Mecanum only: Yaw setpoint
|
||||
|
||||
```
|
||||
@@ -0,0 +1,18 @@
|
||||
# RoverVelocityStatus (UORB message)
|
||||
|
||||
Rover Velocity Status
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocityStatus.msg)
|
||||
|
||||
```c
|
||||
# Rover Velocity Status
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction
|
||||
float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates)
|
||||
float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction
|
||||
float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction
|
||||
float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates)
|
||||
float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction
|
||||
|
||||
```
|
||||
@@ -1,11 +0,0 @@
|
||||
# SensorTemp (UORB message)
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorTemp.msg)
|
||||
|
||||
```c
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
uint32 device_id # unique device ID for the sensor that does not change between power cycles
|
||||
float32 temperature # Temperature provided by sensor (Celsius)
|
||||
|
||||
```
|
||||
@@ -28,7 +28,7 @@ uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circ
|
||||
uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |[m] Major radius|[m] Minor radius|[m/s] Velocity|Orientation|Latitude/X|Longitude/Y|Altitude/Z|
|
||||
uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |[@enum VEHICLE_ROI] Region of interest mode.|MISSION index/ target ID.|ROI index (allows a vehicle to manage multiple ROI's)|Unused|x the location of the fixed ROI (see MAV_FRAME)|y|z|
|
||||
uint16 VEHICLE_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning|0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid|Unused|[deg] [@range 0, 360] Yaw angle at goal, in compass degrees|Latitude/X of goal|Longitude/Y of goal|Altitude/Z of goal|
|
||||
uint16 VEHICLE_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground / hand and transition to fixed wing. |Minimum pitch (if airspeed sensor present), desired pitch without sensor|Transition heading, 0: Default, 3: Use specified transition heading|Unused|Yaw angle (if magnetometer present), ignored without magnetometer|Latitude|Longitude|Altitude|
|
||||
uint16 VEHICLE_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground / hand and transition to fixed wing. |Minimum pitch (if airspeed sensor present), desired pitch without sensor|Unused|Unused|Yaw angle (if magnetometer present), ignored without magnetometer|Latitude|Longitude|Altitude|
|
||||
uint16 VEHICLE_CMD_NAV_VTOL_LAND = 85 # Transition to MC and land at location. |Unused|Unused|Unused|Desired yaw angle.|Latitude|Longitude|Altitude|
|
||||
uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # Set limits for external control. |[s] Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout|[m] Absolute altitude min AMSL - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit|[m] Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit|[m] Horizontal move limit (AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit|Unused|Unused|Unused|
|
||||
uint16 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # Set id of master controller. |System ID|Component ID|Unused|Unused|Unused|Unused|Unused|
|
||||
|
||||
@@ -27,7 +27,7 @@ uint8 ARM_DISARM_REASON_COMMAND_EXTERNAL = 4
|
||||
uint8 ARM_DISARM_REASON_MISSION_START = 5
|
||||
uint8 ARM_DISARM_REASON_LANDING = 6
|
||||
uint8 ARM_DISARM_REASON_PREFLIGHT_INACTION = 7
|
||||
uint8 ARM_DISARM_REASON_KILL_SWITCH = 8
|
||||
uint8 ARM_DISARM_REASON_emergency_stop_switch = 8
|
||||
uint8 ARM_DISARM_REASON_RC_BUTTON = 13
|
||||
uint8 ARM_DISARM_REASON_FAILSAFE = 14
|
||||
|
||||
|
||||
@@ -29,7 +29,7 @@ uint8 ARM_DISARM_REASON_MISSION_START = 5
|
||||
uint8 ARM_DISARM_REASON_SAFETY_BUTTON = 6
|
||||
uint8 ARM_DISARM_REASON_AUTO_DISARM_LAND = 7
|
||||
uint8 ARM_DISARM_REASON_AUTO_DISARM_PREFLIGHT = 8
|
||||
uint8 ARM_DISARM_REASON_KILL_SWITCH = 9
|
||||
uint8 ARM_DISARM_REASON_emergency_stop_switch = 9
|
||||
uint8 ARM_DISARM_REASON_LOCKDOWN = 10
|
||||
uint8 ARM_DISARM_REASON_FAILURE_DETECTOR = 11
|
||||
uint8 ARM_DISARM_REASON_SHUTDOWN = 12
|
||||
|
||||