diff --git a/apps/controller/manual_control/ManualControlSelector.cpp b/apps/controller/manual_control/ManualControlSelector.cpp index f2d373b356..16d72a6ec0 100644 --- a/apps/controller/manual_control/ManualControlSelector.cpp +++ b/apps/controller/manual_control/ManualControlSelector.cpp @@ -29,6 +29,9 @@ void ManualControlSelector::updateWithNewInputSample(uint64_t now, const manual_ const bool start_using_new_input = !_setpoint.valid; // Switch to new input if it's valid and we don't already have a valid one + bool ret = isInputValid(input, now); + rt_kprintf("%d, %d, %d\n", ret, update_existing_input, start_using_new_input); // 1 1 0 + if (isInputValid(input, now) && (update_existing_input || start_using_new_input)) { _setpoint = input; _setpoint.valid = true; @@ -53,7 +56,19 @@ bool ManualControlSelector::isInputValid(const manual_control_setpoint_s &input, const bool source_any_matched = (_rc_in_mode == 2); const bool source_first_matched = (_rc_in_mode == 3) && (input.data_source == _first_valid_source || _first_valid_source == manual_control_setpoint_s::SOURCE_UNKNOWN); - return sample_from_the_past && sample_newer_than_timeout && (source_rc_matched || source_mavlink_matched || source_any_matched || source_first_matched); + // // 正常情况下返回 true + // LOG_I("all ret: %d, %d, %d, %d, %d, %d", + // sample_from_the_past, // ok + // sample_newer_than_timeout, // error + // source_rc_matched, + // source_mavlink_matched, + // source_any_matched, + // source_first_matched); + + // LOG_I("now: %llu, input.timestamp_sample: %llu, _timeout: %llu", now, input.timestamp_sample, _timeout); + + return (sample_from_the_past && sample_newer_than_timeout + && (source_rc_matched || source_mavlink_matched || source_any_matched || source_first_matched)); } manual_control_setpoint_s &ManualControlSelector::setpoint() { diff --git a/apps/estimator/ekf2_fake/ekf2_fake.hpp b/apps/estimator/ekf2_fake/ekf2_fake.hpp index 85427ab835..1150bce0a5 100644 --- a/apps/estimator/ekf2_fake/ekf2_fake.hpp +++ b/apps/estimator/ekf2_fake/ekf2_fake.hpp @@ -16,7 +16,7 @@ using namespace nextpilot; using namespace time_literals; using namespace nextpilot::global_params; -// #define USING_COMMANDER_FAKE +#define USING_COMMANDER_FAKE class EKF2FAKE { public: diff --git a/apps/utest/test_uorb/Kconfig b/apps/utest/test_uorb/Kconfig new file mode 100644 index 0000000000..5fd96baef7 --- /dev/null +++ b/apps/utest/test_uorb/Kconfig @@ -0,0 +1,6 @@ +menuconfig TEST_UORB + bool "test uorb" + default n + +if TEST_UORB +endif diff --git a/apps/utest/test_uorb/SConscript b/apps/utest/test_uorb/SConscript new file mode 100644 index 0000000000..a8a480de8c --- /dev/null +++ b/apps/utest/test_uorb/SConscript @@ -0,0 +1,18 @@ +import os +import rtconfig +from building import * + +cwd = GetCurrentDir() +group = [] + +src = Glob("*.c") + Glob("*.cpp") +inc = [cwd] + +group += DefineGroup("utest", src, depend=[""], CPPPATH=inc) + +for d in os.listdir(cwd): + path = os.path.join(cwd, d) + if os.path.isfile(os.path.join(path, "SConscript")): + group += SConscript(os.path.join(d, "SConscript")) + +Return("group") diff --git a/apps/utest/test_uorb/test_uorb_main.cpp b/apps/utest/test_uorb/test_uorb_main.cpp new file mode 100644 index 0000000000..cf159a13cd --- /dev/null +++ b/apps/utest/test_uorb/test_uorb_main.cpp @@ -0,0 +1,49 @@ +/***************************************************************** + * _ __ __ ____ _ __ __ + * / | / /___ _ __ / /_ / __ \ (_)/ /____ / /_ + * / |/ // _ \ | |/_// __// /_/ // // // __ \ / __/ + * / /| // __/_> < / /_ / ____// // // /_/ // /_ + * /_/ |_/ \___//_/|_| \__//_/ /_//_/ \____/ \__/ + * + * Copyright All Reserved © 2015-2024 NextPilot Development Team + ******************************************************************/ + +#define LOG_TAG "uorb_test_main" +#define LOG_LVL LOG_LVL_INFO + +#include "nextpilot.h" +#include "uorb_pub.hpp" +#include "uorb_sub.hpp" + +char _ut_pub_stack[1024], _ut_sub_stack[1024]; +rt_thread _ut_pub_handle, _ut_sub_handle; + +void ut_pub_entry(void *param) { + while (1) { + uorb_pub::publish_attitude(); + uorb_pub::publish_sensor_accel(); + uorb_pub::publish_sensor_gyro(); + rt_thread_mdelay(1000); + } +} + +void ut_sub_entry(void *param) { + while (1) { + uorb_sub::subscribe_attitude(); + uorb_sub::copy_sensor_accel(); + uorb_sub::subscription_interval_sensor_gyro(); + rt_thread_mdelay(1000); + } +} + +int uorb_test_start() { + rt_err_t ret = RT_EOK; + ret = rt_thread_init(&_ut_pub_handle, "uorb_pub", ut_pub_entry, nullptr, &_ut_pub_stack[0], sizeof(_ut_pub_stack), 10, 5); + ret = rt_thread_init(&_ut_sub_handle, "uorb_sub", ut_sub_entry, nullptr, &_ut_sub_stack[0], sizeof(_ut_sub_stack), 10, 5); + rt_thread_startup(&_ut_pub_handle); + rt_thread_startup(&_ut_sub_handle); + LOG_I("uorb test start"); + return ret; +} + +INIT_APP_EXPORT(uorb_test_start); diff --git a/apps/utest/test_uorb/uorb_pub.hpp b/apps/utest/test_uorb/uorb_pub.hpp new file mode 100644 index 0000000000..ac98cd68ee --- /dev/null +++ b/apps/utest/test_uorb/uorb_pub.hpp @@ -0,0 +1,64 @@ +/***************************************************************** + * _ __ __ ____ _ __ __ + * / | / /___ _ __ / /_ / __ \ (_)/ /____ / /_ + * / |/ // _ \ | |/_// __// /_/ // // // __ \ / __/ + * / /| // __/_> < / /_ / ____// // // /_/ // /_ + * /_/ |_/ \___//_/|_| \__//_/ /_//_/ \____/ \__/ + * + * Copyright All Reserved © 2015-2024 NextPilot Development Team + ******************************************************************/ + +#pragma once + +namespace uorb_pub { +uORB::PublicationData _vehicle_attitude_pub{ORB_ID(vehicle_attitude)}; +uORB::PublicationData _sensor_accel_pub{ORB_ID(sensor_accel)}; +uORB::PublicationData _sensor_gyro_pub{ORB_ID(sensor_gyro)}; + +rt_inline void publish_attitude() { + vehicle_attitude_s att_pub{}; + att_pub.timestamp = 123456789; + att_pub.timestamp_sample = 123456789; + for (int i = 0; i < 4; i++) { + att_pub.q[i] = i; + att_pub.delta_q_reset[i] = i; + } + att_pub.quat_reset_counter = 100; + _vehicle_attitude_pub.publish(att_pub); +}; + +rt_inline void publish_sensor_accel() { + sensor_accel_s sensor_accel{}; + sensor_accel.timestamp = 147258369; + sensor_accel.timestamp_sample = 147258369; + sensor_accel.device_id = 88; + sensor_accel.x = 100; + sensor_accel.y = 200; + sensor_accel.z = 300; + sensor_accel.temperature = 400; + sensor_accel.error_count = 500; + for (int i = 0; i < 3; i++) { + sensor_accel.clip_counter[i] = i * 100; + } + sensor_accel.samples = 123; + _sensor_accel_pub.publish(sensor_accel); +} + +rt_inline void publish_sensor_gyro() { + sensor_gyro_s sensor_gyro{}; + sensor_gyro.timestamp = 147258369; + sensor_gyro.timestamp_sample = 147258369; + sensor_gyro.device_id = 88; + sensor_gyro.x = 100; + sensor_gyro.y = 200; + sensor_gyro.z = 300; + sensor_gyro.temperature = 400; + sensor_gyro.error_count = 500; + for (int i = 0; i < 3; i++) { + sensor_gyro.clip_counter[i] = i * 100; + } + sensor_gyro.samples = 123; + _sensor_gyro_pub.publish(sensor_gyro); +} + +} // namespace uorb_pub diff --git a/apps/utest/test_uorb/uorb_sub.hpp b/apps/utest/test_uorb/uorb_sub.hpp new file mode 100644 index 0000000000..3deb1e9f5d --- /dev/null +++ b/apps/utest/test_uorb/uorb_sub.hpp @@ -0,0 +1,77 @@ +/***************************************************************** + * _ __ __ ____ _ __ __ + * / | / /___ _ __ / /_ / __ \ (_)/ /____ / /_ + * / |/ // _ \ | |/_// __// /_/ // // // __ \ / __/ + * / /| // __/_> < / /_ / ____// // // /_/ // /_ + * /_/ |_/ \___//_/|_| \__//_/ /_//_/ \____/ \__/ + * + * Copyright All Reserved © 2015-2024 NextPilot Development Team + ******************************************************************/ + +#pragma once + +using namespace time_literals; + +namespace uorb_sub { +uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; +uORB::Subscription _sensor_accel_sub{ORB_ID(sensor_accel)}; +uORB::SubscriptionInterval _sensor_gyro_sub{ORB_ID(sensor_gyro), 1_s}; + +rt_inline void subscribe_attitude() { + vehicle_attitude_s att_sub{}; + if (_vehicle_attitude_sub.update(&att_sub)) { + RT_ASSERT(att_sub.timestamp != 123456789); + RT_ASSERT(att_sub.timestamp_sample != 123456789); + for (int i = 0; i < 4; i++) { + RT_ASSERT(att_sub.q[i] != i); + RT_ASSERT(att_sub.delta_q_reset[i] != i); + } + RT_ASSERT(att_sub.quat_reset_counter != 100); + } +} + +rt_inline void copy_sensor_accel() { + sensor_accel_s sensor_accel{}; + if (_sensor_accel_sub.updated()) { + const unsigned last_generation = _sensor_accel_sub.get_last_generation(); + if (_sensor_accel_sub.copy(&sensor_accel)) { + RT_ASSERT(last_generation != last_generation + 1); + RT_ASSERT(sensor_accel.timestamp != 147258369); + RT_ASSERT(sensor_accel.timestamp_sample != 147258369); + RT_ASSERT(sensor_accel.device_id != 88); + RT_ASSERT(sensor_accel.x != 100); + RT_ASSERT(sensor_accel.y != 200); + RT_ASSERT(sensor_accel.z != 300); + RT_ASSERT(sensor_accel.temperature != 400); + RT_ASSERT(sensor_accel.error_count != 500); + for (int i = 0; i < 3; i++) { + RT_ASSERT(sensor_accel.clip_counter[i] != i * 100); + } + RT_ASSERT(sensor_accel.samples != 123); + } + } +} + +rt_inline void subscription_interval_sensor_gyro() { + sensor_gyro_s sensor_gyro{}; + if (_sensor_gyro_sub.updated()) { + const unsigned last_generation = _sensor_gyro_sub.get_last_generation(); + if (_sensor_gyro_sub.copy(&sensor_gyro)) { + RT_ASSERT(last_generation != last_generation + 1); + RT_ASSERT(sensor_gyro.timestamp != 147258369); + RT_ASSERT(sensor_gyro.timestamp_sample != 147258369); + RT_ASSERT(sensor_gyro.device_id != 88); + RT_ASSERT(sensor_gyro.x != 100); + RT_ASSERT(sensor_gyro.y != 200); + RT_ASSERT(sensor_gyro.z != 300); + RT_ASSERT(sensor_gyro.temperature != 400); + RT_ASSERT(sensor_gyro.error_count != 500); + for (int i = 0; i < 3; i++) { + RT_ASSERT(sensor_gyro.clip_counter[i] != i * 100); + } + RT_ASSERT(sensor_gyro.samples != 123); + } + } +} + +} // namespace uorb_sub diff --git a/bsps/px4/fmu-v5/config/utest.config b/bsps/px4/fmu-v5/config/utest.config index 04e4ffd6bd..d4b23daa07 100644 --- a/bsps/px4/fmu-v5/config/utest.config +++ b/bsps/px4/fmu-v5/config/utest.config @@ -1438,6 +1438,7 @@ CONFIG_BOARD_CONSTRAINED_FLASH=y # NextPilot Test Config # CONFIG_TEST_CREATE_THREAD=y +CONFIG_TEST_UORB=y # end of NextPilot Test Config # end of Nextpilot Firmware Config diff --git a/bsps/px4/fmu-v5/project.uvoptx b/bsps/px4/fmu-v5/project.uvoptx index 798d593e8e..e5485c1ab4 100644 --- a/bsps/px4/fmu-v5/project.uvoptx +++ b/bsps/px4/fmu-v5/project.uvoptx @@ -214,8 +214,8 @@ 0 0 0 - board\cubemx\Core\Src\main.c - Src_main.c + board\cubemx\Core\Src\stm32f7xx_hal_msp.c + stm32f7xx_hal_msp.c 0 0 @@ -226,8 +226,8 @@ 0 0 0 - board\cubemx\Core\Src\stm32f7xx_hal_msp.c - stm32f7xx_hal_msp.c + board\cubemx\Core\Src\main.c + Src_main.c 0 0 @@ -258,6 +258,18 @@ 0 0 0 + ports\sd_mnt.c + sd_mnt.c + 0 + 0 + + + 3 + 6 + 1 + 0 + 0 + 0 ports\gpio_init.c gpio_init.c 0 @@ -273,7 +285,7 @@ 0 4 - 6 + 7 1 0 0 @@ -285,7 +297,7 @@ 4 - 7 + 8 1 0 0 @@ -297,7 +309,7 @@ 4 - 8 + 9 1 0 0 @@ -309,7 +321,7 @@ 4 - 9 + 10 1 0 0 @@ -321,7 +333,7 @@ 4 - 10 + 11 1 0 0 @@ -333,7 +345,7 @@ 4 - 11 + 12 1 0 0 @@ -345,7 +357,7 @@ 4 - 12 + 13 1 0 0 @@ -357,7 +369,7 @@ 4 - 13 + 14 1 0 0 @@ -370,14 +382,46 @@ - CPU + CPP 0 0 0 0 5 - 14 + 15 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\cplusplus\cxx_crt_init.c + cxx_crt_init.c + 0 + 0 + + + 5 + 16 + 8 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\cplusplus\cxx_crt.cpp + cxx_crt.cpp + 0 + 0 + + + + + CPU + 0 + 0 + 0 + 0 + + 6 + 17 1 0 0 @@ -388,8 +432,8 @@ 0 - 5 - 15 + 6 + 18 1 0 0 @@ -400,8 +444,8 @@ 0 - 5 - 16 + 6 + 19 1 0 0 @@ -412,8 +456,8 @@ 0 - 5 - 17 + 6 + 20 2 0 0 @@ -424,8 +468,8 @@ 0 - 5 - 18 + 6 + 21 1 0 0 @@ -436,8 +480,8 @@ 0 - 5 - 19 + 6 + 22 1 0 0 @@ -456,8 +500,8 @@ 0 0 - 6 - 20 + 7 + 23 1 0 0 @@ -468,8 +512,8 @@ 0 - 6 - 21 + 7 + 24 1 0 0 @@ -480,8 +524,8 @@ 0 - 6 - 22 + 7 + 25 1 0 0 @@ -492,8 +536,8 @@ 0 - 6 - 23 + 7 + 26 1 0 0 @@ -504,8 +548,8 @@ 0 - 6 - 24 + 7 + 27 1 0 0 @@ -516,8 +560,8 @@ 0 - 6 - 25 + 7 + 28 1 0 0 @@ -528,8 +572,8 @@ 0 - 6 - 26 + 7 + 29 1 0 0 @@ -539,50 +583,6 @@ 0 0 - - 6 - 27 - 1 - 0 - 0 - 0 - ..\..\..\rtos\rt-thread\components\drivers\ipc\workqueue.c - workqueue.c - 0 - 0 - - - 6 - 28 - 1 - 0 - 0 - 0 - ..\..\..\rtos\rt-thread\components\drivers\misc\pin.c - pin.c - 0 - 0 - - - 6 - 29 - 1 - 0 - 0 - 0 - ..\..\..\rtos\rt-thread\components\drivers\serial\serial.c - serial.c - 0 - 0 - - - - - Drivers - 0 - 0 - 0 - 0 7 30 @@ -590,8 +590,8 @@ 0 0 0 - ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_gpio.c - drv_gpio.c + ..\..\..\rtos\rt-thread\components\drivers\ipc\workqueue.c + workqueue.c 0 0 @@ -602,8 +602,8 @@ 0 0 0 - ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_usart.c - drv_usart.c + ..\..\..\rtos\rt-thread\components\drivers\misc\adc.c + adc.c 0 0 @@ -614,588 +614,4164 @@ 0 0 0 - ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_common.c - drv_common.c + ..\..\..\rtos\rt-thread\components\drivers\misc\pin.c + pin.c 0 0 - - - - Filesystem - 0 - 0 - 0 - 0 - 8 + 7 33 1 0 0 0 - ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\devfs\devfs.c - devfs.c + ..\..\..\rtos\rt-thread\components\drivers\misc\rt_drv_pwm.c + rt_drv_pwm.c 0 0 - 8 + 7 34 1 0 0 0 - ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\src\dfs.c - dfs.c + ..\..\..\rtos\rt-thread\components\drivers\rtc\rtc.c + rtc.c 0 0 - 8 + 7 35 1 0 0 0 - ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\src\dfs_file.c - dfs_file.c + ..\..\..\rtos\rt-thread\components\drivers\sdio\block_dev.c + block_dev.c 0 0 - 8 + 7 36 1 0 0 0 - ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\src\dfs_fs.c - dfs_fs.c + ..\..\..\rtos\rt-thread\components\drivers\sdio\gpt.c + gpt.c 0 0 - 8 + 7 37 1 0 0 0 - ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\src\dfs_posix.c - dfs_posix.c + ..\..\..\rtos\rt-thread\components\drivers\sdio\mmc.c + mmc.c 0 0 - - - - Finsh - 0 - 0 - 0 - 0 - 9 + 7 38 1 0 0 0 - ..\..\..\rtos\rt-thread\components\finsh\shell.c - shell.c + ..\..\..\rtos\rt-thread\components\drivers\sdio\mmcsd_core.c + mmcsd_core.c 0 0 - 9 + 7 39 1 0 0 0 - ..\..\..\rtos\rt-thread\components\finsh\msh.c - msh.c + ..\..\..\rtos\rt-thread\components\drivers\sdio\sd.c + sd.c 0 0 - 9 + 7 40 1 0 0 0 - ..\..\..\rtos\rt-thread\components\finsh\msh_parse.c - msh_parse.c + ..\..\..\rtos\rt-thread\components\drivers\sdio\sdio.c + sdio.c 0 0 - 9 + 7 41 1 0 0 0 - ..\..\..\rtos\rt-thread\components\finsh\cmd.c - cmd.c + ..\..\..\rtos\rt-thread\components\drivers\serial\serial.c + serial.c 0 0 - 9 + 7 42 1 0 0 0 - ..\..\..\rtos\rt-thread\components\finsh\msh_file.c - msh_file.c + ..\..\..\rtos\rt-thread\components\drivers\spi\spi_core.c + spi_core.c 0 0 - - - - Kernel - 0 - 0 - 0 - 0 - 10 + 7 43 1 0 0 0 - ..\..\..\rtos\rt-thread\src\clock.c - clock.c + ..\..\..\rtos\rt-thread\components\drivers\spi\spi_dev.c + spi_dev.c 0 0 + + + + Filesystem + 0 + 0 + 0 + 0 - 10 + 8 44 1 0 0 0 - ..\..\..\rtos\rt-thread\src\components.c - components.c + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\devfs\devfs.c + devfs.c 0 0 - 10 + 8 45 1 0 0 0 - ..\..\..\rtos\rt-thread\src\idle.c - idle.c + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\elmfat\dfs_elm.c + dfs_elm.c 0 0 - 10 + 8 46 1 0 0 0 - ..\..\..\rtos\rt-thread\src\ipc.c - ipc.c + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\elmfat\ff.c + ff.c 0 0 - 10 + 8 47 1 0 0 0 - ..\..\..\rtos\rt-thread\src\irq.c - irq.c + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\elmfat\ffunicode.c + ffunicode.c 0 0 - 10 + 8 48 1 0 0 0 - ..\..\..\rtos\rt-thread\src\kservice.c - kservice.c + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\src\dfs.c + dfs.c 0 0 - 10 + 8 49 1 0 0 0 - ..\..\..\rtos\rt-thread\src\mem.c - mem.c + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\src\dfs_file.c + dfs_file.c 0 0 - 10 + 8 50 1 0 0 0 - ..\..\..\rtos\rt-thread\src\mempool.c - mempool.c + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\src\dfs_fs.c + dfs_fs.c 0 0 - 10 + 8 51 1 0 0 0 - ..\..\..\rtos\rt-thread\src\object.c - object.c + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\src\dfs_posix.c + dfs_posix.c 0 0 + + + + Finsh + 0 + 0 + 0 + 0 - 10 + 9 52 1 0 0 0 - ..\..\..\rtos\rt-thread\src\scheduler_up.c - scheduler_up.c + ..\..\..\rtos\rt-thread\components\finsh\cmd.c + cmd.c 0 0 - 10 + 9 53 1 0 0 0 - ..\..\..\rtos\rt-thread\src\thread.c - thread.c + ..\..\..\rtos\rt-thread\components\finsh\msh.c + msh.c 0 0 - 10 + 9 54 1 0 0 0 - ..\..\..\rtos\rt-thread\src\timer.c - timer.c + ..\..\..\rtos\rt-thread\components\finsh\shell.c + shell.c 0 0 - - - - Libraries - 0 - 0 - 0 - 0 - 11 + 9 55 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal.c - stm32f7xx_hal.c + ..\..\..\rtos\rt-thread\components\finsh\msh_parse.c + msh_parse.c 0 0 - 11 + 9 56 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_uart_ex.c - stm32f7xx_hal_uart_ex.c + ..\..\..\rtos\rt-thread\components\finsh\msh_file.c + msh_file.c 0 0 + + + + hal/stm32f7 + 0 + 0 + 0 + 0 - 11 + 10 57 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_pwr.c - stm32f7xx_hal_pwr.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_spi_ex.c + stm32f7xx_hal_spi_ex.c 0 0 - 11 + 10 58 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_sram.c - stm32f7xx_hal_sram.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_uart.c + stm32f7xx_hal_uart.c 0 0 - 11 + 10 59 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rcc_ex.c - stm32f7xx_hal_rcc_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_crc_ex.c + stm32f7xx_hal_crc_ex.c 0 0 - 11 + 10 60 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_crc.c - stm32f7xx_hal_crc.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_tim.c + stm32f7xx_hal_tim.c 0 0 - 11 + 10 61 - 1 + 2 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_usart.c - stm32f7xx_hal_usart.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Source\Templates\arm\startup_stm32f765xx.s + startup_stm32f765xx.s 0 0 - 11 + 10 62 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rcc.c - stm32f7xx_hal_rcc.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_dma_ex.c + stm32f7xx_hal_dma_ex.c 0 0 - 11 + 10 63 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cec.c - stm32f7xx_hal_cec.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_sram.c + stm32f7xx_hal_sram.c 0 0 - 11 + 10 64 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cryp.c - stm32f7xx_hal_cryp.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_exti.c + stm32f7xx_hal_exti.c 0 0 - 11 + 10 65 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_gpio.c - stm32f7xx_hal_gpio.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_tim_ex.c + stm32f7xx_hal_tim_ex.c 0 0 - 11 + 10 66 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_exti.c - stm32f7xx_hal_exti.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_pwr_ex.c + stm32f7xx_hal_pwr_ex.c 0 0 - 11 + 10 67 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cryp_ex.c - stm32f7xx_hal_cryp_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_sd.c + stm32f7xx_hal_sd.c 0 0 - 11 + 10 68 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_dma_ex.c - stm32f7xx_hal_dma_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_usart.c + stm32f7xx_hal_usart.c 0 0 - 11 + 10 69 - 2 + 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Source\Templates\arm\startup_stm32f765xx.s - startup_stm32f765xx.s + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rcc.c + stm32f7xx_hal_rcc.c 0 0 - 11 + 10 70 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cortex.c - stm32f7xx_hal_cortex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_spi.c + stm32f7xx_hal_spi.c 0 0 - 11 + 10 71 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_dma.c - stm32f7xx_hal_dma.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_qspi.c + stm32f7xx_hal_qspi.c 0 0 - 11 + 10 72 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Source\Templates\system_stm32f7xx.c - system_stm32f7xx.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cortex.c + stm32f7xx_hal_cortex.c 0 0 - 11 + 10 73 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_uart.c - stm32f7xx_hal_uart.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cec.c + stm32f7xx_hal_cec.c 0 0 - 11 + 10 74 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_pwr_ex.c - stm32f7xx_hal_pwr_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rtc_ex.c + stm32f7xx_hal_rtc_ex.c 0 0 - 11 + 10 75 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rng.c - stm32f7xx_hal_rng.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rtc.c + stm32f7xx_hal_rtc.c 0 0 - 11 + 10 76 1 0 0 0 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_crc_ex.c - stm32f7xx_hal_crc_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cryp_ex.c + stm32f7xx_hal_cryp_ex.c 0 0 - - - - pkg/common - 0 - 0 - 0 - 0 - 12 + 10 77 - 8 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_lptim.c + stm32f7xx_hal_lptim.c + 0 + 0 + + + 10 + 78 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_ll_sdmmc.c + stm32f7xx_ll_sdmmc.c + 0 + 0 + + + 10 + 79 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_crc.c + stm32f7xx_hal_crc.c + 0 + 0 + + + 10 + 80 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_adc.c + stm32f7xx_hal_adc.c + 0 + 0 + + + 10 + 81 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cryp.c + stm32f7xx_hal_cryp.c + 0 + 0 + + + 10 + 82 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_gpio.c + stm32f7xx_hal_gpio.c + 0 + 0 + + + 10 + 83 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_pwr.c + stm32f7xx_hal_pwr.c + 0 + 0 + + + 10 + 84 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Source\Templates\system_stm32f7xx.c + system_stm32f7xx.c + 0 + 0 + + + 10 + 85 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_uart_ex.c + stm32f7xx_hal_uart_ex.c + 0 + 0 + + + 10 + 86 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_adc_ex.c + stm32f7xx_hal_adc_ex.c + 0 + 0 + + + 10 + 87 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rng.c + stm32f7xx_hal_rng.c + 0 + 0 + + + 10 + 88 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal.c + stm32f7xx_hal.c + 0 + 0 + + + 10 + 89 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rcc_ex.c + stm32f7xx_hal_rcc_ex.c + 0 + 0 + + + 10 + 90 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_dma.c + stm32f7xx_hal_dma.c + 0 + 0 + + + + + Kernel + 0 + 0 + 0 + 0 + + 11 + 91 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\clock.c + clock.c + 0 + 0 + + + 11 + 92 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\components.c + components.c + 0 + 0 + + + 11 + 93 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\idle.c + idle.c + 0 + 0 + + + 11 + 94 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\ipc.c + ipc.c + 0 + 0 + + + 11 + 95 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\irq.c + irq.c + 0 + 0 + + + 11 + 96 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\kservice.c + kservice.c + 0 + 0 + + + 11 + 97 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\mem.c + mem.c + 0 + 0 + + + 11 + 98 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\mempool.c + mempool.c + 0 + 0 + + + 11 + 99 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\object.c + object.c + 0 + 0 + + + 11 + 100 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\scheduler_up.c + scheduler_up.c + 0 + 0 + + + 11 + 101 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\thread.c + thread.c + 0 + 0 + + + 11 + 102 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\src\timer.c + timer.c + 0 + 0 + + + + + ktime + 0 + 0 + 0 + 0 + + 12 + 103 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\drivers\ktime\src\cputimer.c + cputimer.c + 0 + 0 + + + 12 + 104 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\drivers\ktime\src\boottime.c + boottime.c + 0 + 0 + + + 12 + 105 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\drivers\ktime\src\hrtimer.c + hrtimer.c + 0 + 0 + + + + + Legacy + 0 + 0 + 0 + 0 + + 13 + 106 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\legacy\ipc\workqueue_legacy.c + workqueue_legacy.c + 0 + 0 + + + + + lib/common + 0 + 0 + 0 + 0 + + 14 + 107 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\hrtimer\V3\callout_using_ostimer.c + callout_using_ostimer.c + 0 + 0 + + + 14 + 108 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\hrtimer\V3\timestamp_using_systick.c + timestamp_using_systick.c + 0 + 0 + + + 14 + 109 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\hrtimer\V3\hrtimer.c + V3_hrtimer.c + 0 + 0 + + + + + lib/console_buffer + 0 + 0 + 0 + 0 + + 15 + 110 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\console_buffer\console_buffer.cpp + console_buffer.cpp + 0 + 0 + + + + + lib/ring_buffer + 0 + 0 + 0 + 0 + + 16 + 111 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\ringbuffer\Ringbuffer.cpp + Ringbuffer.cpp + 0 + 0 + + + + + pkg/common + 0 + 0 + 0 + 0 + + 17 + 112 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_addafter.c + dq_addafter.c + 0 + 0 + + + 17 + 113 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_rem.c + sq_rem.c + 0 + 0 + + + 17 + 114 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_remlast.c + sq_remlast.c + 0 + 0 + + + 17 + 115 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_addfirst.c + dq_addfirst.c + 0 + 0 + + + 17 + 116 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_addlast.c + sq_addlast.c + 0 + 0 + + + 17 + 117 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_count.c + dq_count.c + 0 + 0 + + + 17 + 118 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_remfirst.c + dq_remfirst.c + 0 + 0 + + + 17 + 119 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_remlast.c + dq_remlast.c + 0 + 0 + + + 17 + 120 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_rem.c + dq_rem.c + 0 + 0 + + + 17 + 121 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_addfirst.c + sq_addfirst.c + 0 + 0 + + + 17 + 122 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_addafter.c + sq_addafter.c + 0 + 0 + + + 17 + 123 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_remafter.c + sq_remafter.c + 0 + 0 + + + 17 + 124 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_addlast.c + dq_addlast.c + 0 + 0 + + + 17 + 125 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_cat.c + sq_cat.c + 0 + 0 + + + 17 + 126 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_remfirst.c + sq_remfirst.c + 0 + 0 + + + 17 + 127 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_addbefore.c + dq_addbefore.c + 0 + 0 + + + 17 + 128 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\sq_count.c + sq_count.c + 0 + 0 + + + 17 + 129 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\queue\dq_cat.c + dq_cat.c + 0 + 0 + + + + + pkg/events + 0 + 0 + 0 + 0 + + 18 + 130 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\events\events.cpp + events.cpp + 0 + 0 + + + + + pkg/getopt + 0 + 0 + 0 + 0 + + 19 + 131 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\getopt\getopt.c + getopt.c + 0 + 0 + + + + + pkg/libcrc + 0 + 0 + 0 + 0 + + 20 + 132 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\libcrc\lib_crc8ccitt.c + lib_crc8ccitt.c + 0 + 0 + + + 20 + 133 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\libcrc\lib_crc8.c + lib_crc8.c + 0 + 0 + + + 20 + 134 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\libcrc\lib_crc16.c + lib_crc16.c + 0 + 0 + + + 20 + 135 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\libcrc\lib_crc32.c + lib_crc32.c + 0 + 0 + + + 20 + 136 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\libcrc\lib_crc64.c + lib_crc64.c + 0 + 0 + + + + + pkg/param + 0 + 0 + 0 + 0 + + 21 + 137 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\param\param_interface.c + param_interface.c + 0 + 0 + + + 21 + 138 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\param\param_storage.c + param_storage.c + 0 + 0 + + + 21 + 139 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\param\interface\param_global_autogen.cpp + param_global_autogen.cpp + 0 + 0 + + + 21 + 140 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\param\param.c + param.c + 0 + 0 + + + 21 + 141 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\param\storage\param_storage_file.c + param_storage_file.c + 0 + 0 + + + + + pkg/perf + 0 + 0 + 0 + 0 + + 22 + 142 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\perf\perf_counter.cpp + perf_counter.cpp + 0 + 0 + + + + + pkg/uorb + 0 + 0 + 0 + 0 + + 23 + 143 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\power_button_state.cpp + power_button_state.cpp + 0 + 0 + + + 23 + 144 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\power_monitor.cpp + power_monitor.cpp + 0 + 0 + + + 23 + 145 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_accel_fifo.cpp + sensor_accel_fifo.cpp + 0 + 0 + + + 23 + 146 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\cpuload.cpp + cpuload.cpp + 0 + 0 + + + 23 + 147 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\ulog_stream.cpp + ulog_stream.cpp + 0 + 0 + + + 23 + 148 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\landing_target_innovations.cpp + landing_target_innovations.cpp + 0 + 0 + + + 23 + 149 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\orb_test_large.cpp + orb_test_large.cpp + 0 + 0 + + + 23 + 150 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\actuator_armed.cpp + actuator_armed.cpp + 0 + 0 + + + 23 + 151 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_imu.cpp + vehicle_imu.cpp + 0 + 0 + + + 23 + 152 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_status.cpp + estimator_status.cpp + 0 + 0 + + + 23 + 153 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_constraints.cpp + vehicle_constraints.cpp + 0 + 0 + + + 23 + 154 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gimbal_manager_set_manual_control.cpp + gimbal_manager_set_manual_control.cpp + 0 + 0 + + + 23 + 155 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\pps_capture.cpp + pps_capture.cpp + 0 + 0 + + + 23 + 156 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\control_allocator_status.cpp + control_allocator_status.cpp + 0 + 0 + + + 23 + 157 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\Publication.cpp + Publication.cpp + 0 + 0 + + + 23 + 158 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_sensor_bias.cpp + estimator_sensor_bias.cpp + 0 + 0 + + + 23 + 159 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_angular_velocity.cpp + vehicle_angular_velocity.cpp + 0 + 0 + + + 23 + 160 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\heater_status.cpp + heater_status.cpp + 0 + 0 + + + 23 + 161 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\mavlink_tunnel.cpp + mavlink_tunnel.cpp + 0 + 0 + + + 23 + 162 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\action_request.cpp + action_request.cpp + 0 + 0 + + + 23 + 163 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\uORB.cpp + uORB.cpp + 0 + 0 + + + 23 + 164 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\collision_constraints.cpp + collision_constraints.cpp + 0 + 0 + + + 23 + 165 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\timesync_status.cpp + timesync_status.cpp + 0 + 0 + + + 23 + 166 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\differential_pressure.cpp + differential_pressure.cpp + 0 + 0 + + + 23 + 167 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\log_message.cpp + log_message.cpp + 0 + 0 + + + 23 + 168 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\px4io_status.cpp + px4io_status.cpp + 0 + 0 + + + 23 + 169 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\navigator_mission_item.cpp + navigator_mission_item.cpp + 0 + 0 + + + 23 + 170 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_baro.cpp + sensor_baro.cpp + 0 + 0 + + + 23 + 171 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\debug_array.cpp + debug_array.cpp + 0 + 0 + + + 23 + 172 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_command.cpp + vehicle_command.cpp + 0 + 0 + + + 23 + 173 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\failsafe_flags.cpp + failsafe_flags.cpp + 0 + 0 + + + 23 + 174 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\uavcan_parameter_value.cpp + uavcan_parameter_value.cpp + 0 + 0 + + + 23 + 175 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\obstacle_distance.cpp + obstacle_distance.cpp + 0 + 0 + + + 23 + 176 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\autotune_attitude_control_status.cpp + autotune_attitude_control_status.cpp + 0 + 0 + + + 23 + 177 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_gyro_fft.cpp + sensor_gyro_fft.cpp + 0 + 0 + + + 23 + 178 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_status_flags.cpp + estimator_status_flags.cpp + 0 + 0 + + + 23 + 179 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\position_controller_landing_status.cpp + position_controller_landing_status.cpp + 0 + 0 + + + 23 + 180 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\qshell_req.cpp + qshell_req.cpp + 0 + 0 + + + 23 + 181 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\airspeed.cpp + airspeed.cpp + 0 + 0 + + + 23 + 182 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_combined.cpp + sensor_combined.cpp + 0 + 0 + + + 23 + 183 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\debug_value.cpp + debug_value.cpp + 0 + 0 + + + 23 + 184 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_global_position.cpp + vehicle_global_position.cpp + 0 + 0 + + + 23 + 185 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\landing_target_pose.cpp + landing_target_pose.cpp + 0 + 0 + + + 23 + 186 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gripper.cpp + gripper.cpp + 0 + 0 + + + 23 + 187 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\offboard_control_mode.cpp + offboard_control_mode.cpp + 0 + 0 + + + 23 + 188 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\mode_completed.cpp + mode_completed.cpp + 0 + 0 + + + 23 + 189 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\camera_capture.cpp + camera_capture.cpp + 0 + 0 + + + 23 + 190 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_gyro_fifo.cpp + sensor_gyro_fifo.cpp + 0 + 0 + + + 23 + 191 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_correction.cpp + sensor_correction.cpp + 0 + 0 + + + 23 + 192 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_aid_source1d.cpp + estimator_aid_source1d.cpp + 0 + 0 + + + 23 + 193 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\ulog_stream_ack.cpp + ulog_stream_ack.cpp + 0 + 0 + + + 23 + 194 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_bias3d.cpp + estimator_bias3d.cpp + 0 + 0 + + + 23 + 195 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_attitude.cpp + vehicle_attitude.cpp + 0 + 0 + + + 23 + 196 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\magnetometer_bias_estimate.cpp + magnetometer_bias_estimate.cpp + 0 + 0 + + + 23 + 197 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\yaw_estimator_status.cpp + yaw_estimator_status.cpp + 0 + 0 + + + 23 + 198 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\hover_thrust_estimate.cpp + hover_thrust_estimate.cpp + 0 + 0 + + + 23 + 199 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\npfg_status.cpp + npfg_status.cpp + 0 + 0 + + + 23 + 200 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\cellular_status.cpp + cellular_status.cpp + 0 + 0 + + + 23 + 201 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\takeoff_status.cpp + takeoff_status.cpp + 0 + 0 + + + 23 + 202 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_gyro.cpp + sensor_gyro.cpp + 0 + 0 + + + 23 + 203 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\trajectory_setpoint.cpp + trajectory_setpoint.cpp + 0 + 0 + + + 23 + 204 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\landing_gear_wheel.cpp + landing_gear_wheel.cpp + 0 + 0 + + + 23 + 205 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gimbal_device_attitude_status.cpp + gimbal_device_attitude_status.cpp + 0 + 0 + + + 23 + 206 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\collision_report.cpp + collision_report.cpp + 0 + 0 + + + 23 + 207 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_mag.cpp + sensor_mag.cpp + 0 + 0 + + + 23 + 208 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_preflight_mag.cpp + sensor_preflight_mag.cpp + 0 + 0 + + + 23 + 209 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\follow_target.cpp + follow_target.cpp + 0 + 0 + + + 23 + 210 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_odometry.cpp + vehicle_odometry.cpp + 0 + 0 + + + 23 + 211 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\landing_gear.cpp + landing_gear.cpp + 0 + 0 + + + 23 + 212 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\position_controller_status.cpp + position_controller_status.cpp + 0 + 0 + + + 23 + 213 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\qshell_retval.cpp + qshell_retval.cpp + 0 + 0 + + + 23 + 214 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\rc_channels.cpp + rc_channels.cpp + 0 + 0 + + + 23 + 215 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\airspeed_validated.cpp + airspeed_validated.cpp + 0 + 0 + + + 23 + 216 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_states.cpp + estimator_states.cpp + 0 + 0 + + + 23 + 217 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_land_detected.cpp + vehicle_land_detected.cpp + 0 + 0 + + + 23 + 218 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\uavcan_parameter_request.cpp + uavcan_parameter_request.cpp + 0 + 0 + + + 23 + 219 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\home_position.cpp + home_position.cpp + 0 + 0 + + + 23 + 220 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\orb_test.cpp + orb_test.cpp + 0 + 0 + + + 23 + 221 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\uORBManager.cpp + uORBManager.cpp + 0 + 0 + + + 23 + 222 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\rc_parameter_map.cpp + rc_parameter_map.cpp + 0 + 0 + + + 23 + 223 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_hygrometer.cpp + sensor_hygrometer.cpp + 0 + 0 + + + 23 + 224 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\trajectory_bezier.cpp + trajectory_bezier.cpp + 0 + 0 + + + 23 + 225 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_control_mode.cpp + vehicle_control_mode.cpp + 0 + 0 + + + 23 + 226 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\follow_target_status.cpp + follow_target_status.cpp + 0 + 0 + + + 23 + 227 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_optical_flow.cpp + vehicle_optical_flow.cpp + 0 + 0 + + + 23 + 228 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gimbal_manager_status.cpp + gimbal_manager_status.cpp + 0 + 0 + + + 23 + 229 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vtol_vehicle_status.cpp + vtol_vehicle_status.cpp + 0 + 0 + + + 23 + 230 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\mavlink_log.cpp + mavlink_log.cpp + 0 + 0 + + + 23 + 231 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\ekf2_timestamps.cpp + ekf2_timestamps.cpp + 0 + 0 + + + 23 + 232 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_aid_source2d.cpp + estimator_aid_source2d.cpp + 0 + 0 + + + 23 + 233 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\tune_control.cpp + tune_control.cpp + 0 + 0 + + + 23 + 234 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gimbal_manager_information.cpp + gimbal_manager_information.cpp + 0 + 0 + + + 23 + 235 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\input_rc.cpp + input_rc.cpp + 0 + 0 + + + 23 + 236 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\mission.cpp + mission.cpp + 0 + 0 + + + 23 + 237 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_bias.cpp + estimator_bias.cpp + 0 + 0 + + + 23 + 238 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gimbal_manager_set_attitude.cpp + gimbal_manager_set_attitude.cpp + 0 + 0 + + + 23 + 239 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_trajectory_bezier.cpp + vehicle_trajectory_bezier.cpp + 0 + 0 + + + 23 + 240 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\Subscription.cpp + Subscription.cpp + 0 + 0 + + + 23 + 241 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\adc_report.cpp + adc_report.cpp + 0 + 0 + + + 23 + 242 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_aid_source3d.cpp + estimator_aid_source3d.cpp + 0 + 0 + + + 23 + 243 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_imu_status.cpp + vehicle_imu_status.cpp + 0 + 0 + + + 23 + 244 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gps_dump.cpp + gps_dump.cpp + 0 + 0 + + + 23 + 245 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\internal_combustion_engine_status.cpp + internal_combustion_engine_status.cpp + 0 + 0 + + + 23 + 246 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\orb_test_medium.cpp + orb_test_medium.cpp + 0 + 0 + + + 23 + 247 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\position_setpoint.cpp + position_setpoint.cpp + 0 + 0 + + + 23 + 248 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_gps_status.cpp + estimator_gps_status.cpp + 0 + 0 + + + 23 + 249 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\generator_status.cpp + generator_status.cpp + 0 + 0 + + + 23 + 250 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_optical_flow_vel.cpp + vehicle_optical_flow_vel.cpp + 0 + 0 + + + 23 + 251 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_status.cpp + vehicle_status.cpp + 0 + 0 + + + 23 + 252 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_trajectory_waypoint.cpp + vehicle_trajectory_waypoint.cpp + 0 + 0 + + + 23 + 253 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\orbit_status.cpp + orbit_status.cpp + 0 + 0 + + + 23 + 254 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\airspeed_wind.cpp + airspeed_wind.cpp + 0 + 0 + + + 23 + 255 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_uwb.cpp + sensor_uwb.cpp + 0 + 0 + + + 23 + 256 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\event.cpp + event.cpp + 0 + 0 + + + 23 + 257 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_magnetometer.cpp + vehicle_magnetometer.cpp + 0 + 0 + + + 23 + 258 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\iridiumsbd_status.cpp + iridiumsbd_status.cpp + 0 + 0 + + + 23 + 259 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_thrust_setpoint.cpp + vehicle_thrust_setpoint.cpp + 0 + 0 + + + 23 + 260 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\position_setpoint_triplet.cpp + position_setpoint_triplet.cpp + 0 + 0 + + + 23 + 261 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_optical_flow.cpp + sensor_optical_flow.cpp + 0 + 0 + + + 23 + 262 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\radio_status.cpp + radio_status.cpp + 0 + 0 + + + 23 + 263 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\distance_sensor.cpp + distance_sensor.cpp + 0 + 0 + + + 23 + 264 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gimbal_device_set_attitude.cpp + gimbal_device_set_attitude.cpp + 0 + 0 + + + 23 + 265 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gimbal_device_information.cpp + gimbal_device_information.cpp + 0 + 0 + + + 23 + 266 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\wind.cpp + wind.cpp + 0 + 0 + + + 23 + 267 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\mission_result.cpp + mission_result.cpp + 0 + 0 + + + 23 + 268 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\actuator_servos.cpp + actuator_servos.cpp + 0 + 0 + + + 23 + 269 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\rpm.cpp + rpm.cpp + 0 + 0 + + + 23 + 270 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\battery_status.cpp + battery_status.cpp + 0 + 0 + + + 23 + 271 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\system_power.cpp + system_power.cpp + 0 + 0 + + + 23 + 272 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_air_data.cpp + vehicle_air_data.cpp + 0 + 0 + + + 23 + 273 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\debug_key_value.cpp + debug_key_value.cpp + 0 + 0 + + + 23 + 274 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_angular_acceleration_setpoint.cpp + vehicle_angular_acceleration_setpoint.cpp + 0 + 0 + + + 23 + 275 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\led_control.cpp + led_control.cpp + 0 + 0 + + + 23 + 276 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\normalized_unsigned_setpoint.cpp + normalized_unsigned_setpoint.cpp + 0 + 0 + + + 23 + 277 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\DeviceNode.cpp + DeviceNode.cpp + 0 + 0 + + + 23 + 278 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\actuator_test.cpp + actuator_test.cpp + 0 + 0 + + + 23 + 279 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\task_stack_info.cpp + task_stack_info.cpp + 0 + 0 + + + 23 + 280 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_attitude_setpoint.cpp + vehicle_attitude_setpoint.cpp + 0 + 0 + + + 23 + 281 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\esc_status.cpp + esc_status.cpp + 0 + 0 + + + 23 + 282 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_command_ack.cpp + vehicle_command_ack.cpp + 0 + 0 + + + 23 + 283 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_rates_setpoint.cpp + vehicle_rates_setpoint.cpp + 0 + 0 + + + 23 + 284 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\health_report.cpp + health_report.cpp + 0 + 0 + + + 23 + 285 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\manual_control_setpoint.cpp + manual_control_setpoint.cpp + 0 + 0 + + + 23 + 286 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\actuator_servos_trim.cpp + actuator_servos_trim.cpp + 0 + 0 + + + 23 + 287 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\rtl_time_estimate.cpp + rtl_time_estimate.cpp + 0 + 0 + + + 23 + 288 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\button_event.cpp + button_event.cpp + 0 + 0 + + + 23 + 289 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_acceleration.cpp + vehicle_acceleration.cpp + 0 + 0 + + + 23 + 290 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\parameter_update.cpp + parameter_update.cpp + 0 + 0 + + + 23 + 291 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_selection.cpp + sensor_selection.cpp + 0 + 0 + + + 23 + 292 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\rate_ctrl_status.cpp + rate_ctrl_status.cpp + 0 + 0 + + + 23 + 293 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\transponder_report.cpp + transponder_report.cpp + 0 + 0 + + + 23 + 294 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gimbal_controls.cpp + gimbal_controls.cpp + 0 + 0 + + + 23 + 295 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\onboard_computer_status.cpp + onboard_computer_status.cpp + 0 + 0 + + + 23 + 296 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\actuator_motors.cpp + actuator_motors.cpp + 0 + 0 + + + 23 + 297 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\tecs_status.cpp + tecs_status.cpp + 0 + 0 + + + 23 + 298 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensors_status_imu.cpp + sensors_status_imu.cpp + 0 + 0 + + + 23 + 299 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\esc_report.cpp + esc_report.cpp + 0 + 0 + + + 23 + 300 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_local_position.cpp + vehicle_local_position.cpp + 0 + 0 + + + 23 + 301 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_event_flags.cpp + estimator_event_flags.cpp + 0 + 0 + + + 23 + 302 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_local_position_setpoint.cpp + vehicle_local_position_setpoint.cpp + 0 + 0 + + + 23 + 303 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\mount_orientation.cpp + mount_orientation.cpp + 0 + 0 + + + 23 + 304 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\satellite_info.cpp + satellite_info.cpp + 0 + 0 + + + 23 + 305 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_innovations.cpp + estimator_innovations.cpp + 0 + 0 + + + 23 + 306 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\trajectory_waypoint.cpp + trajectory_waypoint.cpp + 0 + 0 + + + 23 + 307 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\geofence_result.cpp + geofence_result.cpp + 0 + 0 + + + 23 + 308 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_roi.cpp + vehicle_roi.cpp + 0 + 0 + + + 23 + 309 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\pwm_input.cpp + pwm_input.cpp + 0 + 0 + + + 23 + 310 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensors_status.cpp + sensors_status.cpp + 0 + 0 + + + 23 + 311 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_accel.cpp + sensor_accel.cpp + 0 + 0 + + + 23 + 312 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\camera_status.cpp + camera_status.cpp + 0 + 0 + + + 23 + 313 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\telemetry_status.cpp + telemetry_status.cpp + 0 + 0 + + + 23 + 314 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\debug_vect.cpp + debug_vect.cpp + 0 + 0 + + + 23 + 315 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\estimator_selector_status.cpp + estimator_selector_status.cpp + 0 + 0 + + + 23 + 316 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\logger_status.cpp + logger_status.cpp + 0 + 0 + + + 23 + 317 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\irlock_report.cpp + irlock_report.cpp + 0 + 0 + + + 23 + 318 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\vehicle_torque_setpoint.cpp + vehicle_torque_setpoint.cpp + 0 + 0 + + + 23 + 319 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\ping.cpp + ping.cpp + 0 + 0 + + + 23 + 320 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\manual_control_switches.cpp + manual_control_switches.cpp + 0 + 0 + + + 23 + 321 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\actuator_outputs.cpp + actuator_outputs.cpp + 0 + 0 + + + 23 + 322 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\tiltrotor_extra_controls.cpp + tiltrotor_extra_controls.cpp + 0 + 0 + + + 23 + 323 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\uORBTopics.cpp + uORBTopics.cpp + 0 + 0 + + + 23 + 324 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\failure_detector_status.cpp + failure_detector_status.cpp + 0 + 0 + + + 23 + 325 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\gps_inject_data.cpp + gps_inject_data.cpp + 0 + 0 + + + 23 + 326 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\mag_worker_data.cpp + mag_worker_data.cpp + 0 + 0 + + + 23 + 327 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_gnss_relative.cpp + sensor_gnss_relative.cpp + 0 + 0 + + + 23 + 328 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\actuator_controls_status.cpp + actuator_controls_status.cpp + 0 + 0 + + + 23 + 329 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\sensor_gps.cpp + sensor_gps.cpp + 0 + 0 + + + 23 + 330 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\camera_trigger.cpp + camera_trigger.cpp + 0 + 0 + + + 23 + 331 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\follow_target_estimator.cpp + follow_target_estimator.cpp + 0 + 0 + + + 23 + 332 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\uORB\topics\launch_detection_status.cpp + launch_detection_status.cpp + 0 + 0 + + + + + pkg/vconsole + 0 + 0 + 0 + 0 + + 24 + 333 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\vconsole\vconsole.c + vconsole.c + 0 + 0 + + + + + pkg/version + 0 + 0 + 0 + 0 + + 25 + 334 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\variable_length_ringbuffer\VariableLengthRingbuffer.cpp + VariableLengthRingbuffer.cpp + 0 + 0 + + + 25 + 335 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\version\board_fw_version.c + board_fw_version.c + 0 + 0 + + + 25 + 336 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\version\board_hw_version.c + board_hw_version.c + 0 + 0 + + + 25 + 337 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\version\board_mcu_version.c + board_mcu_version.c + 0 + 0 + + + 25 + 338 + 1 + 0 + 0 + 0 + ..\..\..\pkgs\version\board_version_main.c + board_version_main.c + 0 + 0 + + + + + pkg/workq + 0 + 0 + 0 + 0 + + 26 + 339 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\workq\WorkQueue.cpp + WorkQueue.cpp + 0 + 0 + + + 26 + 340 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\workq\WorkItemScheduled.cpp + WorkItemScheduled.cpp + 0 + 0 + + + 26 + 341 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\workq\WorkItemSingleShot.cpp + WorkItemSingleShot.cpp + 0 + 0 + + + 26 + 342 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\workq\WorkQueueManager.cpp + WorkQueueManager.cpp + 0 + 0 + + + 26 + 343 + 8 + 0 + 0 + 0 + ..\..\..\pkgs\workq\WorkItem.cpp + WorkItem.cpp + 0 + 0 + + + + + POSIX + 0 + 0 + 0 + 0 + + 27 + 344 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\delay\delay.c + delay.c + 0 + 0 + + + 27 + 345 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread.c + pthread.c + 0 + 0 + + + 27 + 346 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_attr.c + pthread_attr.c + 0 + 0 + + + 27 + 347 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_barrier.c + pthread_barrier.c + 0 + 0 + + + 27 + 348 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_cond.c + pthread_cond.c + 0 + 0 + + + 27 + 349 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_mutex.c + pthread_mutex.c + 0 + 0 + + + 27 + 350 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_rwlock.c + pthread_rwlock.c + 0 + 0 + + + 27 + 351 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_spin.c + pthread_spin.c + 0 + 0 + + + 27 + 352 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_tls.c + pthread_tls.c + 0 + 0 + + + 27 + 353 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\sched.c + sched.c + 0 + 0 + + + + + rtt/Drivers + 0 + 0 + 0 + 0 + + 28 + 354 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_usart.c + drv_usart.c + 0 + 0 + + + 28 + 355 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_common.c + drv_common.c + 0 + 0 + + + 28 + 356 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_gpio.c + drv_gpio.c + 0 + 0 + + + 28 + 357 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_spi.c + drv_spi.c + 0 + 0 + + + 28 + 358 + 1 + 0 + 0 + 0 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_adc.c + drv_adc.c + 0 + 0 + + + + + utest + 0 + 0 + 0 + 0 + + 29 + 359 + 8 + 0 + 0 + 0 + ..\..\..\apps\utest\test_thread\test_thread.cpp + test_thread.cpp + 0 + 0 + + + 29 + 360 + 8 + 0 + 0 + 0 + ..\..\..\apps\utest\test_uorb\test_uorb_main.cpp + test_uorb_main.cpp + 0 + 0 + + + + + Utilities + 0 + 0 + 0 + 0 + + 30 + 361 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\utilities\ulog\ulog.c + ulog.c + 0 + 0 + + + 30 + 362 + 1 + 0 + 0 + 0 + ..\..\..\rtos\rt-thread\components\utilities\ulog\backend\console_be.c + console_be.c + 0 + 0 + + + 30 + 363 + 1 0 0 0 - ..\..\..\pkgs\device\device.cpp - device_device.cpp + ..\..\..\rtos\rt-thread\components\utilities\ulog\backend\file_be.c + file_be.c 0 0 diff --git a/bsps/px4/fmu-v5/project.uvprojx b/bsps/px4/fmu-v5/project.uvprojx index 92facb267e..ba040b72f8 100644 --- a/bsps/px4/fmu-v5/project.uvprojx +++ b/bsps/px4/fmu-v5/project.uvprojx @@ -314,7 +314,7 @@ 1 - 3 + 1 0 0 1 @@ -330,7 +330,7 @@ 0 0 5 - 6 + 8 1 1 0 @@ -338,9 +338,9 @@ 0 - __STDC_LIMIT_MACROS, RT_USING_ARMLIBC, USE_HAL_DRIVER, RT_USING_LIBC, __CLK_TCK=RT_TICK_PER_SECOND, STM32F765xx, __RTTHREAD__ + __RTTHREAD__, __CLK_TCK=RT_TICK_PER_SECOND, RT_USING_LIBC, __STDC_LIMIT_MACROS, RT_USING_ARMLIBC, STM32F765xx, USE_HAL_DRIVER - ..\..\..\pkgs;..\..\..\pkgs\include;..\..\..\rtos\platform\stm32\HAL_Drivers\CMSIS\Include;ports;..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Include;..\..\..\rtos\rt-thread\libcpu\arm\cortex-m7;..\..\..\rtos\platform\stm32\HAL_Drivers;..\..\..\apps\storage;..\..\..\apps\libraries\peripheral;board;..\..\..\apps\libraries\peripheral\rcinput;..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\devfs;..\..\..\rtos\rt-thread\include;..\..\..\rtos\rt-thread\components\libc\posix\io\epoll;..\..\..\rtos\rt-thread\components\libc\posix\io\poll;..\..\..\apps;..\..\..\apps\estimator;..\..\..\rtos\rt-thread\components\libc\compilers\common\include;..\..\..\apps\libraries\peripheral\notification;..\..\..\rtos\rt-thread\libcpu\arm\common;..\..\..\rtos\rt-thread\components\libc\compilers\common\extension\fcntl\octal;..\..\..\rtos\rt-thread\components\libc\posix\io\eventfd;..\..\..\pkgs\module;..\..\..\apps\libraries\peripheral\battery;..\..\..\pkgs\ulog;..\..\..\apps\libraries\telemetry;board\cubemx\Core\Inc;..\..\..\apps\libraries\controller;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\pkgs\atomic;..\..\..\apps\libraries\peripheral\payload;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\rtos\rt-thread\components\dfs\dfs_v1\include;..\..\..\apps\libraries\estimator;..\..\..\rtos\platform\stm32\HAL_Drivers\config;..\..\..\apps\controller;..\..\..\apps\libraries\peripheral\sensor;..\..\..\rtos\rt-thread\components\finsh;..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Inc;..\..\..\rtos\rt-thread\components\libc\posix\ipc;applications;..\..\..\rtos\rt-thread\components\libc\compilers\common\extension;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\rtos\rt-thread\components\drivers\include;. + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads;..\..\..\pkgs\queue;..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Inc;..\..\..\rtos\rt-thread\components\libc\posix\delay;..\..\..\rtos\rt-thread\components\libc\compilers\common\include;..\..\..\pkgs\include;..\..\..\apps\libraries\peripheral\battery;..\..\..\pkgs\version;..\..\..\pkgs;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\apps\libraries\peripheral\sensor;..\..\..\rtos\rt-thread\components\libc\compilers\common\extension\fcntl\octal;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\pkgs\perf;..\..\..\pkgs\atomic;..\..\..\apps\utest\test_uorb;..\..\..\pkgs\uORB;..\..\..\pkgs\param\wrapper;..\..\..\pkgs\containers;..\..\..\apps\libraries\peripheral\payload;..\..\..\rtos\platform\stm32\HAL_Drivers;board;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\pkgs\events;..\..\..\pkgs\libcrc;..\..\..\pkgs\console_buffer;..\..\..\pkgs\param\storage;..\..\..\rtos\rt-thread\components\libc\posix\io\epoll;..\..\..\pkgs\mathlib;..\..\..\apps\libraries\controller;..\..\..\pkgs\hrtimer\V3;..\..\..\rtos\rt-thread\components\utilities\ulog;..\..\..\rtos\platform\stm32\HAL_Drivers\config;..\..\..\pkgs\ringbuffer;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\rtos\rt-thread\components\finsh;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\apps\libraries\peripheral\rcinput;..\..\..\rtos\rt-thread\components\libc\posix\ipc;..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Include;..\..\..\rtos\rt-thread\components\libc\cplusplus;..\..\..\apps\libraries\peripheral;..\..\..\rtos\rt-thread\include;..\..\..\pkgs\param\interface;..\..\..\pkgs\workq;..\..\..\rtos\rt-thread\components\legacy\dfs;..\..\..\pkgs\module;..\..\..\apps;..\..\..\rtos\rt-thread\components\libc\posix\io\poll;ports;..\..\..\apps\estimator;..\..\..\pkgs\mathlib\math\filter;..\..\..\rtos\platform\stm32\HAL_Drivers\CMSIS\Include;..\..\..\apps\libraries\estimator;..\..\..\rtos\rt-thread\components\drivers\ktime\inc;board\cubemx\Core\Inc;..\..\..\apps\utest;..\..\..\rtos\rt-thread\libcpu\arm\cortex-m7;..\..\..\rtos\rt-thread\components\libc\compilers\common\extension;..\..\..\rtos\rt-thread\libcpu\arm\common;applications;..\..\..\apps\libraries\peripheral\notification;..\..\..\pkgs\matrix;..\..\..\apps\libraries\telemetry;..\..\..\rtos\rt-thread\components\libc\posix\io\eventfd;..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\devfs;..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\elmfat;..\..\..\rtos\rt-thread\components\drivers\ktime;.;..\..\..\apps\utest\test_thread;..\..\..\apps\storage;..\..\..\pkgs\vconsole;..\..\..\rtos\rt-thread\components\drivers\spi;..\..\..\pkgs\ulog;..\..\..\rtos\rt-thread\components\utilities\ulog\backend;..\..\..\rtos\rt-thread\components\dfs\dfs_v1\include;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\pkgs\param;..\..\..\rtos\rt-thread\components\legacy;..\..\..\rtos\rt-thread\components\drivers\include;..\..\..\apps\controller @@ -395,14 +395,14 @@ bsp/board - Src_main.c + stm32f7xx_hal_msp.c 1 - board\cubemx\Core\Src\main.c + board\cubemx\Core\Src\stm32f7xx_hal_msp.c - stm32f7xx_hal_msp.c + Src_main.c 1 - board\cubemx\Core\Src\stm32f7xx_hal_msp.c + board\cubemx\Core\Src\main.c board.c @@ -414,6 +414,11 @@ bsp/ports + + sd_mnt.c + 1 + ports\sd_mnt.c + gpio_init.c 1 @@ -466,6 +471,21 @@ + + CPP + + + cxx_crt_init.c + 1 + ..\..\..\rtos\rt-thread\components\libc\cplusplus\cxx_crt_init.c + + + cxx_crt.cpp + 8 + ..\..\..\rtos\rt-thread\components\libc\cplusplus\cxx_crt.cpp + + + CPU @@ -544,35 +564,70 @@ 1 ..\..\..\rtos\rt-thread\components\drivers\ipc\workqueue.c + + adc.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\misc\adc.c + pin.c 1 ..\..\..\rtos\rt-thread\components\drivers\misc\pin.c - serial.c + rt_drv_pwm.c 1 - ..\..\..\rtos\rt-thread\components\drivers\serial\serial.c + ..\..\..\rtos\rt-thread\components\drivers\misc\rt_drv_pwm.c - - - - Drivers - - drv_gpio.c + rtc.c 1 - ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_gpio.c + ..\..\..\rtos\rt-thread\components\drivers\rtc\rtc.c - drv_usart.c + block_dev.c 1 - ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_usart.c + ..\..\..\rtos\rt-thread\components\drivers\sdio\block_dev.c - drv_common.c + gpt.c 1 - ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_common.c + ..\..\..\rtos\rt-thread\components\drivers\sdio\gpt.c + + + mmc.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\sdio\mmc.c + + + mmcsd_core.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\sdio\mmcsd_core.c + + + sd.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\sdio\sd.c + + + sdio.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\sdio\sdio.c + + + serial.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\serial\serial.c + + + spi_core.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\spi\spi_core.c + + + spi_dev.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\spi\spi_dev.c @@ -584,6 +639,21 @@ 1 ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\devfs\devfs.c + + dfs_elm.c + 1 + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\elmfat\dfs_elm.c + + + ff.c + 1 + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\elmfat\ff.c + + + ffunicode.c + 1 + ..\..\..\rtos\rt-thread\components\dfs\dfs_v1\filesystems\elmfat\ffunicode.c + dfs.c 1 @@ -610,9 +680,9 @@ Finsh - shell.c + cmd.c 1 - ..\..\..\rtos\rt-thread\components\finsh\shell.c + ..\..\..\rtos\rt-thread\components\finsh\cmd.c msh.c @@ -620,14 +690,14 @@ ..\..\..\rtos\rt-thread\components\finsh\msh.c - msh_parse.c + shell.c 1 - ..\..\..\rtos\rt-thread\components\finsh\msh_parse.c + ..\..\..\rtos\rt-thread\components\finsh\shell.c - cmd.c + msh_parse.c 1 - ..\..\..\rtos\rt-thread\components\finsh\cmd.c + ..\..\..\rtos\rt-thread\components\finsh\msh_parse.c msh_file.c @@ -637,117 +707,127 @@ - Kernel + hal/stm32f7 - clock.c + stm32f7xx_hal_spi_ex.c 1 - ..\..\..\rtos\rt-thread\src\clock.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_spi_ex.c - components.c + stm32f7xx_hal_uart.c 1 - ..\..\..\rtos\rt-thread\src\components.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_uart.c - idle.c + stm32f7xx_hal_crc_ex.c 1 - ..\..\..\rtos\rt-thread\src\idle.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_crc_ex.c - ipc.c + stm32f7xx_hal_tim.c 1 - ..\..\..\rtos\rt-thread\src\ipc.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_tim.c - irq.c + startup_stm32f765xx.s + 2 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Source\Templates\arm\startup_stm32f765xx.s + + + stm32f7xx_hal_dma_ex.c 1 - ..\..\..\rtos\rt-thread\src\irq.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_dma_ex.c - kservice.c + stm32f7xx_hal_sram.c 1 - ..\..\..\rtos\rt-thread\src\kservice.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_sram.c - mem.c + stm32f7xx_hal_exti.c 1 - ..\..\..\rtos\rt-thread\src\mem.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_exti.c - mempool.c + stm32f7xx_hal_tim_ex.c 1 - ..\..\..\rtos\rt-thread\src\mempool.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_tim_ex.c - object.c + stm32f7xx_hal_pwr_ex.c 1 - ..\..\..\rtos\rt-thread\src\object.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_pwr_ex.c - scheduler_up.c + stm32f7xx_hal_sd.c 1 - ..\..\..\rtos\rt-thread\src\scheduler_up.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_sd.c - thread.c + stm32f7xx_hal_usart.c 1 - ..\..\..\rtos\rt-thread\src\thread.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_usart.c - timer.c + stm32f7xx_hal_rcc.c 1 - ..\..\..\rtos\rt-thread\src\timer.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rcc.c - - - - Libraries - - stm32f7xx_hal.c + stm32f7xx_hal_spi.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_spi.c - stm32f7xx_hal_uart_ex.c + stm32f7xx_hal_qspi.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_uart_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_qspi.c - stm32f7xx_hal_pwr.c + stm32f7xx_hal_cortex.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_pwr.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cortex.c - stm32f7xx_hal_sram.c + stm32f7xx_hal_cec.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_sram.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cec.c - stm32f7xx_hal_rcc_ex.c + stm32f7xx_hal_rtc_ex.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rcc_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rtc_ex.c - stm32f7xx_hal_crc.c + stm32f7xx_hal_rtc.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_crc.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rtc.c - stm32f7xx_hal_usart.c + stm32f7xx_hal_cryp_ex.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_usart.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cryp_ex.c - stm32f7xx_hal_rcc.c + stm32f7xx_hal_lptim.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rcc.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_lptim.c - stm32f7xx_hal_cec.c + stm32f7xx_ll_sdmmc.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cec.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_ll_sdmmc.c + + + stm32f7xx_hal_crc.c + 1 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_crc.c + + + stm32f7xx_hal_adc.c + 1 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_adc.c stm32f7xx_hal_cryp.c @@ -760,138 +840,1509 @@ ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_gpio.c - stm32f7xx_hal_exti.c + stm32f7xx_hal_pwr.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_exti.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_pwr.c - stm32f7xx_hal_cryp_ex.c + system_stm32f7xx.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cryp_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Source\Templates\system_stm32f7xx.c - stm32f7xx_hal_dma_ex.c + stm32f7xx_hal_uart_ex.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_dma_ex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_uart_ex.c - startup_stm32f765xx.s - 2 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Source\Templates\arm\startup_stm32f765xx.s + stm32f7xx_hal_adc_ex.c + 1 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_adc_ex.c - stm32f7xx_hal_cortex.c + stm32f7xx_hal_rng.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_cortex.c + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rng.c + + + stm32f7xx_hal.c + 1 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal.c + + + stm32f7xx_hal_rcc_ex.c + 1 + ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rcc_ex.c stm32f7xx_hal_dma.c 1 ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_dma.c + + + + Kernel + - system_stm32f7xx.c + clock.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\CMSIS\Device\ST\STM32F7xx\Source\Templates\system_stm32f7xx.c + ..\..\..\rtos\rt-thread\src\clock.c - stm32f7xx_hal_uart.c + components.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_uart.c + ..\..\..\rtos\rt-thread\src\components.c - stm32f7xx_hal_pwr_ex.c + idle.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_pwr_ex.c + ..\..\..\rtos\rt-thread\src\idle.c - stm32f7xx_hal_rng.c + ipc.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_rng.c + ..\..\..\rtos\rt-thread\src\ipc.c - stm32f7xx_hal_crc_ex.c + irq.c 1 - ..\..\..\rtos\platform\stm32\STM32F7xx_HAL\STM32F7xx_HAL_Driver\Src\stm32f7xx_hal_crc_ex.c + ..\..\..\rtos\rt-thread\src\irq.c + + + kservice.c + 1 + ..\..\..\rtos\rt-thread\src\kservice.c + + + mem.c + 1 + ..\..\..\rtos\rt-thread\src\mem.c + + + mempool.c + 1 + ..\..\..\rtos\rt-thread\src\mempool.c + + + object.c + 1 + ..\..\..\rtos\rt-thread\src\object.c + + + scheduler_up.c + 1 + ..\..\..\rtos\rt-thread\src\scheduler_up.c + + + thread.c + 1 + ..\..\..\rtos\rt-thread\src\thread.c + + + timer.c + 1 + ..\..\..\rtos\rt-thread\src\timer.c - pkg/common - - - 0 - 0 - 0 - 0 - 0 - 0 - 2 - 2 - 2 - 2 - 11 - - - 1 - - - - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 0 - 0 - 2 - 2 - 2 - 2 - 2 - - - - - - - - - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - - - - - - - - - + ktime - device_device.cpp - 8 - ..\..\..\pkgs\device\device.cpp + cputimer.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\ktime\src\cputimer.c + + + boottime.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\ktime\src\boottime.c + + + hrtimer.c + 1 + ..\..\..\rtos\rt-thread\components\drivers\ktime\src\hrtimer.c + + + + + Legacy + + + workqueue_legacy.c + 1 + ..\..\..\rtos\rt-thread\components\legacy\ipc\workqueue_legacy.c + + + + + lib/common + + + callout_using_ostimer.c + 1 + ..\..\..\pkgs\hrtimer\V3\callout_using_ostimer.c + + + timestamp_using_systick.c + 1 + ..\..\..\pkgs\hrtimer\V3\timestamp_using_systick.c + + + V3_hrtimer.c + 1 + ..\..\..\pkgs\hrtimer\V3\hrtimer.c + + + + + lib/console_buffer + + + console_buffer.cpp + 8 + ..\..\..\pkgs\console_buffer\console_buffer.cpp + + + + + lib/ring_buffer + + + Ringbuffer.cpp + 8 + ..\..\..\pkgs\ringbuffer\Ringbuffer.cpp + + + + + pkg/common + + + dq_addafter.c + 1 + ..\..\..\pkgs\queue\dq_addafter.c + + + sq_rem.c + 1 + ..\..\..\pkgs\queue\sq_rem.c + + + sq_remlast.c + 1 + ..\..\..\pkgs\queue\sq_remlast.c + + + dq_addfirst.c + 1 + ..\..\..\pkgs\queue\dq_addfirst.c + + + sq_addlast.c + 1 + ..\..\..\pkgs\queue\sq_addlast.c + + + dq_count.c + 1 + ..\..\..\pkgs\queue\dq_count.c + + + dq_remfirst.c + 1 + ..\..\..\pkgs\queue\dq_remfirst.c + + + dq_remlast.c + 1 + ..\..\..\pkgs\queue\dq_remlast.c + + + dq_rem.c + 1 + ..\..\..\pkgs\queue\dq_rem.c + + + sq_addfirst.c + 1 + ..\..\..\pkgs\queue\sq_addfirst.c + + + sq_addafter.c + 1 + ..\..\..\pkgs\queue\sq_addafter.c + + + sq_remafter.c + 1 + ..\..\..\pkgs\queue\sq_remafter.c + + + dq_addlast.c + 1 + ..\..\..\pkgs\queue\dq_addlast.c + + + sq_cat.c + 1 + ..\..\..\pkgs\queue\sq_cat.c + + + sq_remfirst.c + 1 + ..\..\..\pkgs\queue\sq_remfirst.c + + + dq_addbefore.c + 1 + ..\..\..\pkgs\queue\dq_addbefore.c + + + sq_count.c + 1 + ..\..\..\pkgs\queue\sq_count.c + + + dq_cat.c + 1 + ..\..\..\pkgs\queue\dq_cat.c + + + + + pkg/events + + + events.cpp + 8 + ..\..\..\pkgs\events\events.cpp + + + + + pkg/getopt + + + getopt.c + 1 + ..\..\..\pkgs\getopt\getopt.c + + + + + pkg/libcrc + + + lib_crc8ccitt.c + 1 + ..\..\..\pkgs\libcrc\lib_crc8ccitt.c + + + lib_crc8.c + 1 + ..\..\..\pkgs\libcrc\lib_crc8.c + + + lib_crc16.c + 1 + ..\..\..\pkgs\libcrc\lib_crc16.c + + + lib_crc32.c + 1 + ..\..\..\pkgs\libcrc\lib_crc32.c + + + lib_crc64.c + 1 + ..\..\..\pkgs\libcrc\lib_crc64.c + + + + + pkg/param + + + param_interface.c + 1 + ..\..\..\pkgs\param\param_interface.c + + + param_storage.c + 1 + ..\..\..\pkgs\param\param_storage.c + + + param_global_autogen.cpp + 8 + ..\..\..\pkgs\param\interface\param_global_autogen.cpp + + + param.c + 1 + ..\..\..\pkgs\param\param.c + + + param_storage_file.c + 1 + ..\..\..\pkgs\param\storage\param_storage_file.c + + + + + pkg/perf + + + perf_counter.cpp + 8 + ..\..\..\pkgs\perf\perf_counter.cpp + + + + + pkg/uorb + + + power_button_state.cpp + 8 + ..\..\..\pkgs\uORB\topics\power_button_state.cpp + + + power_monitor.cpp + 8 + ..\..\..\pkgs\uORB\topics\power_monitor.cpp + + + sensor_accel_fifo.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_accel_fifo.cpp + + + cpuload.cpp + 8 + ..\..\..\pkgs\uORB\topics\cpuload.cpp + + + ulog_stream.cpp + 8 + ..\..\..\pkgs\uORB\topics\ulog_stream.cpp + + + landing_target_innovations.cpp + 8 + ..\..\..\pkgs\uORB\topics\landing_target_innovations.cpp + + + orb_test_large.cpp + 8 + ..\..\..\pkgs\uORB\topics\orb_test_large.cpp + + + actuator_armed.cpp + 8 + ..\..\..\pkgs\uORB\topics\actuator_armed.cpp + + + vehicle_imu.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_imu.cpp + + + estimator_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_status.cpp + + + vehicle_constraints.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_constraints.cpp + + + gimbal_manager_set_manual_control.cpp + 8 + ..\..\..\pkgs\uORB\topics\gimbal_manager_set_manual_control.cpp + + + pps_capture.cpp + 8 + ..\..\..\pkgs\uORB\topics\pps_capture.cpp + + + control_allocator_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\control_allocator_status.cpp + + + Publication.cpp + 8 + ..\..\..\pkgs\uORB\Publication.cpp + + + estimator_sensor_bias.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_sensor_bias.cpp + + + vehicle_angular_velocity.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_angular_velocity.cpp + + + heater_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\heater_status.cpp + + + mavlink_tunnel.cpp + 8 + ..\..\..\pkgs\uORB\topics\mavlink_tunnel.cpp + + + action_request.cpp + 8 + ..\..\..\pkgs\uORB\topics\action_request.cpp + + + uORB.cpp + 8 + ..\..\..\pkgs\uORB\uORB.cpp + + + collision_constraints.cpp + 8 + ..\..\..\pkgs\uORB\topics\collision_constraints.cpp + + + timesync_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\timesync_status.cpp + + + differential_pressure.cpp + 8 + ..\..\..\pkgs\uORB\topics\differential_pressure.cpp + + + log_message.cpp + 8 + ..\..\..\pkgs\uORB\topics\log_message.cpp + + + px4io_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\px4io_status.cpp + + + navigator_mission_item.cpp + 8 + ..\..\..\pkgs\uORB\topics\navigator_mission_item.cpp + + + sensor_baro.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_baro.cpp + + + debug_array.cpp + 8 + ..\..\..\pkgs\uORB\topics\debug_array.cpp + + + vehicle_command.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_command.cpp + + + failsafe_flags.cpp + 8 + ..\..\..\pkgs\uORB\topics\failsafe_flags.cpp + + + uavcan_parameter_value.cpp + 8 + ..\..\..\pkgs\uORB\topics\uavcan_parameter_value.cpp + + + obstacle_distance.cpp + 8 + ..\..\..\pkgs\uORB\topics\obstacle_distance.cpp + + + autotune_attitude_control_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\autotune_attitude_control_status.cpp + + + sensor_gyro_fft.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_gyro_fft.cpp + + + estimator_status_flags.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_status_flags.cpp + + + position_controller_landing_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\position_controller_landing_status.cpp + + + qshell_req.cpp + 8 + ..\..\..\pkgs\uORB\topics\qshell_req.cpp + + + airspeed.cpp + 8 + ..\..\..\pkgs\uORB\topics\airspeed.cpp + + + sensor_combined.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_combined.cpp + + + debug_value.cpp + 8 + ..\..\..\pkgs\uORB\topics\debug_value.cpp + + + vehicle_global_position.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_global_position.cpp + + + landing_target_pose.cpp + 8 + ..\..\..\pkgs\uORB\topics\landing_target_pose.cpp + + + gripper.cpp + 8 + ..\..\..\pkgs\uORB\topics\gripper.cpp + + + offboard_control_mode.cpp + 8 + ..\..\..\pkgs\uORB\topics\offboard_control_mode.cpp + + + mode_completed.cpp + 8 + ..\..\..\pkgs\uORB\topics\mode_completed.cpp + + + camera_capture.cpp + 8 + ..\..\..\pkgs\uORB\topics\camera_capture.cpp + + + sensor_gyro_fifo.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_gyro_fifo.cpp + + + sensor_correction.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_correction.cpp + + + estimator_aid_source1d.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_aid_source1d.cpp + + + ulog_stream_ack.cpp + 8 + ..\..\..\pkgs\uORB\topics\ulog_stream_ack.cpp + + + estimator_bias3d.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_bias3d.cpp + + + vehicle_attitude.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_attitude.cpp + + + magnetometer_bias_estimate.cpp + 8 + ..\..\..\pkgs\uORB\topics\magnetometer_bias_estimate.cpp + + + yaw_estimator_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\yaw_estimator_status.cpp + + + hover_thrust_estimate.cpp + 8 + ..\..\..\pkgs\uORB\topics\hover_thrust_estimate.cpp + + + npfg_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\npfg_status.cpp + + + cellular_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\cellular_status.cpp + + + takeoff_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\takeoff_status.cpp + + + sensor_gyro.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_gyro.cpp + + + trajectory_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\trajectory_setpoint.cpp + + + landing_gear_wheel.cpp + 8 + ..\..\..\pkgs\uORB\topics\landing_gear_wheel.cpp + + + gimbal_device_attitude_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\gimbal_device_attitude_status.cpp + + + collision_report.cpp + 8 + ..\..\..\pkgs\uORB\topics\collision_report.cpp + + + sensor_mag.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_mag.cpp + + + sensor_preflight_mag.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_preflight_mag.cpp + + + follow_target.cpp + 8 + ..\..\..\pkgs\uORB\topics\follow_target.cpp + + + vehicle_odometry.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_odometry.cpp + + + landing_gear.cpp + 8 + ..\..\..\pkgs\uORB\topics\landing_gear.cpp + + + position_controller_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\position_controller_status.cpp + + + qshell_retval.cpp + 8 + ..\..\..\pkgs\uORB\topics\qshell_retval.cpp + + + rc_channels.cpp + 8 + ..\..\..\pkgs\uORB\topics\rc_channels.cpp + + + airspeed_validated.cpp + 8 + ..\..\..\pkgs\uORB\topics\airspeed_validated.cpp + + + estimator_states.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_states.cpp + + + vehicle_land_detected.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_land_detected.cpp + + + uavcan_parameter_request.cpp + 8 + ..\..\..\pkgs\uORB\topics\uavcan_parameter_request.cpp + + + home_position.cpp + 8 + ..\..\..\pkgs\uORB\topics\home_position.cpp + + + orb_test.cpp + 8 + ..\..\..\pkgs\uORB\topics\orb_test.cpp + + + uORBManager.cpp + 8 + ..\..\..\pkgs\uORB\uORBManager.cpp + + + rc_parameter_map.cpp + 8 + ..\..\..\pkgs\uORB\topics\rc_parameter_map.cpp + + + sensor_hygrometer.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_hygrometer.cpp + + + trajectory_bezier.cpp + 8 + ..\..\..\pkgs\uORB\topics\trajectory_bezier.cpp + + + vehicle_control_mode.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_control_mode.cpp + + + follow_target_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\follow_target_status.cpp + + + vehicle_optical_flow.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_optical_flow.cpp + + + gimbal_manager_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\gimbal_manager_status.cpp + + + vtol_vehicle_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\vtol_vehicle_status.cpp + + + mavlink_log.cpp + 8 + ..\..\..\pkgs\uORB\topics\mavlink_log.cpp + + + ekf2_timestamps.cpp + 8 + ..\..\..\pkgs\uORB\topics\ekf2_timestamps.cpp + + + estimator_aid_source2d.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_aid_source2d.cpp + + + tune_control.cpp + 8 + ..\..\..\pkgs\uORB\topics\tune_control.cpp + + + gimbal_manager_information.cpp + 8 + ..\..\..\pkgs\uORB\topics\gimbal_manager_information.cpp + + + input_rc.cpp + 8 + ..\..\..\pkgs\uORB\topics\input_rc.cpp + + + mission.cpp + 8 + ..\..\..\pkgs\uORB\topics\mission.cpp + + + estimator_bias.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_bias.cpp + + + gimbal_manager_set_attitude.cpp + 8 + ..\..\..\pkgs\uORB\topics\gimbal_manager_set_attitude.cpp + + + vehicle_trajectory_bezier.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_trajectory_bezier.cpp + + + Subscription.cpp + 8 + ..\..\..\pkgs\uORB\Subscription.cpp + + + adc_report.cpp + 8 + ..\..\..\pkgs\uORB\topics\adc_report.cpp + + + estimator_aid_source3d.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_aid_source3d.cpp + + + vehicle_imu_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_imu_status.cpp + + + gps_dump.cpp + 8 + ..\..\..\pkgs\uORB\topics\gps_dump.cpp + + + internal_combustion_engine_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\internal_combustion_engine_status.cpp + + + orb_test_medium.cpp + 8 + ..\..\..\pkgs\uORB\topics\orb_test_medium.cpp + + + position_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\position_setpoint.cpp + + + estimator_gps_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_gps_status.cpp + + + generator_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\generator_status.cpp + + + vehicle_optical_flow_vel.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_optical_flow_vel.cpp + + + vehicle_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_status.cpp + + + vehicle_trajectory_waypoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_trajectory_waypoint.cpp + + + orbit_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\orbit_status.cpp + + + airspeed_wind.cpp + 8 + ..\..\..\pkgs\uORB\topics\airspeed_wind.cpp + + + sensor_uwb.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_uwb.cpp + + + event.cpp + 8 + ..\..\..\pkgs\uORB\topics\event.cpp + + + vehicle_magnetometer.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_magnetometer.cpp + + + iridiumsbd_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\iridiumsbd_status.cpp + + + vehicle_thrust_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_thrust_setpoint.cpp + + + position_setpoint_triplet.cpp + 8 + ..\..\..\pkgs\uORB\topics\position_setpoint_triplet.cpp + + + sensor_optical_flow.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_optical_flow.cpp + + + radio_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\radio_status.cpp + + + distance_sensor.cpp + 8 + ..\..\..\pkgs\uORB\topics\distance_sensor.cpp + + + gimbal_device_set_attitude.cpp + 8 + ..\..\..\pkgs\uORB\topics\gimbal_device_set_attitude.cpp + + + gimbal_device_information.cpp + 8 + ..\..\..\pkgs\uORB\topics\gimbal_device_information.cpp + + + wind.cpp + 8 + ..\..\..\pkgs\uORB\topics\wind.cpp + + + mission_result.cpp + 8 + ..\..\..\pkgs\uORB\topics\mission_result.cpp + + + actuator_servos.cpp + 8 + ..\..\..\pkgs\uORB\topics\actuator_servos.cpp + + + rpm.cpp + 8 + ..\..\..\pkgs\uORB\topics\rpm.cpp + + + battery_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\battery_status.cpp + + + system_power.cpp + 8 + ..\..\..\pkgs\uORB\topics\system_power.cpp + + + vehicle_air_data.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_air_data.cpp + + + debug_key_value.cpp + 8 + ..\..\..\pkgs\uORB\topics\debug_key_value.cpp + + + vehicle_angular_acceleration_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_angular_acceleration_setpoint.cpp + + + led_control.cpp + 8 + ..\..\..\pkgs\uORB\topics\led_control.cpp + + + normalized_unsigned_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\normalized_unsigned_setpoint.cpp + + + DeviceNode.cpp + 8 + ..\..\..\pkgs\uORB\DeviceNode.cpp + + + actuator_test.cpp + 8 + ..\..\..\pkgs\uORB\topics\actuator_test.cpp + + + task_stack_info.cpp + 8 + ..\..\..\pkgs\uORB\topics\task_stack_info.cpp + + + vehicle_attitude_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_attitude_setpoint.cpp + + + esc_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\esc_status.cpp + + + vehicle_command_ack.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_command_ack.cpp + + + vehicle_rates_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_rates_setpoint.cpp + + + health_report.cpp + 8 + ..\..\..\pkgs\uORB\topics\health_report.cpp + + + manual_control_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\manual_control_setpoint.cpp + + + actuator_servos_trim.cpp + 8 + ..\..\..\pkgs\uORB\topics\actuator_servos_trim.cpp + + + rtl_time_estimate.cpp + 8 + ..\..\..\pkgs\uORB\topics\rtl_time_estimate.cpp + + + button_event.cpp + 8 + ..\..\..\pkgs\uORB\topics\button_event.cpp + + + vehicle_acceleration.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_acceleration.cpp + + + parameter_update.cpp + 8 + ..\..\..\pkgs\uORB\topics\parameter_update.cpp + + + sensor_selection.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_selection.cpp + + + rate_ctrl_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\rate_ctrl_status.cpp + + + transponder_report.cpp + 8 + ..\..\..\pkgs\uORB\topics\transponder_report.cpp + + + gimbal_controls.cpp + 8 + ..\..\..\pkgs\uORB\topics\gimbal_controls.cpp + + + onboard_computer_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\onboard_computer_status.cpp + + + actuator_motors.cpp + 8 + ..\..\..\pkgs\uORB\topics\actuator_motors.cpp + + + tecs_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\tecs_status.cpp + + + sensors_status_imu.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensors_status_imu.cpp + + + esc_report.cpp + 8 + ..\..\..\pkgs\uORB\topics\esc_report.cpp + + + vehicle_local_position.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_local_position.cpp + + + estimator_event_flags.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_event_flags.cpp + + + vehicle_local_position_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_local_position_setpoint.cpp + + + mount_orientation.cpp + 8 + ..\..\..\pkgs\uORB\topics\mount_orientation.cpp + + + satellite_info.cpp + 8 + ..\..\..\pkgs\uORB\topics\satellite_info.cpp + + + estimator_innovations.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_innovations.cpp + + + trajectory_waypoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\trajectory_waypoint.cpp + + + geofence_result.cpp + 8 + ..\..\..\pkgs\uORB\topics\geofence_result.cpp + + + vehicle_roi.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_roi.cpp + + + pwm_input.cpp + 8 + ..\..\..\pkgs\uORB\topics\pwm_input.cpp + + + sensors_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensors_status.cpp + + + sensor_accel.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_accel.cpp + + + camera_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\camera_status.cpp + + + telemetry_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\telemetry_status.cpp + + + debug_vect.cpp + 8 + ..\..\..\pkgs\uORB\topics\debug_vect.cpp + + + estimator_selector_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\estimator_selector_status.cpp + + + logger_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\logger_status.cpp + + + irlock_report.cpp + 8 + ..\..\..\pkgs\uORB\topics\irlock_report.cpp + + + vehicle_torque_setpoint.cpp + 8 + ..\..\..\pkgs\uORB\topics\vehicle_torque_setpoint.cpp + + + ping.cpp + 8 + ..\..\..\pkgs\uORB\topics\ping.cpp + + + manual_control_switches.cpp + 8 + ..\..\..\pkgs\uORB\topics\manual_control_switches.cpp + + + actuator_outputs.cpp + 8 + ..\..\..\pkgs\uORB\topics\actuator_outputs.cpp + + + tiltrotor_extra_controls.cpp + 8 + ..\..\..\pkgs\uORB\topics\tiltrotor_extra_controls.cpp + + + uORBTopics.cpp + 8 + ..\..\..\pkgs\uORB\topics\uORBTopics.cpp + + + failure_detector_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\failure_detector_status.cpp + + + gps_inject_data.cpp + 8 + ..\..\..\pkgs\uORB\topics\gps_inject_data.cpp + + + mag_worker_data.cpp + 8 + ..\..\..\pkgs\uORB\topics\mag_worker_data.cpp + + + sensor_gnss_relative.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_gnss_relative.cpp + + + actuator_controls_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\actuator_controls_status.cpp + + + sensor_gps.cpp + 8 + ..\..\..\pkgs\uORB\topics\sensor_gps.cpp + + + camera_trigger.cpp + 8 + ..\..\..\pkgs\uORB\topics\camera_trigger.cpp + + + follow_target_estimator.cpp + 8 + ..\..\..\pkgs\uORB\topics\follow_target_estimator.cpp + + + launch_detection_status.cpp + 8 + ..\..\..\pkgs\uORB\topics\launch_detection_status.cpp + + + + + pkg/vconsole + + + vconsole.c + 1 + ..\..\..\pkgs\vconsole\vconsole.c + + + + + pkg/version + + + VariableLengthRingbuffer.cpp + 8 + ..\..\..\pkgs\variable_length_ringbuffer\VariableLengthRingbuffer.cpp + + + board_fw_version.c + 1 + ..\..\..\pkgs\version\board_fw_version.c + + + board_hw_version.c + 1 + ..\..\..\pkgs\version\board_hw_version.c + + + board_mcu_version.c + 1 + ..\..\..\pkgs\version\board_mcu_version.c + + + board_version_main.c + 1 + ..\..\..\pkgs\version\board_version_main.c + + + + + pkg/workq + + + WorkQueue.cpp + 8 + ..\..\..\pkgs\workq\WorkQueue.cpp + + + WorkItemScheduled.cpp + 8 + ..\..\..\pkgs\workq\WorkItemScheduled.cpp + + + WorkItemSingleShot.cpp + 8 + ..\..\..\pkgs\workq\WorkItemSingleShot.cpp + + + WorkQueueManager.cpp + 8 + ..\..\..\pkgs\workq\WorkQueueManager.cpp + + + WorkItem.cpp + 8 + ..\..\..\pkgs\workq\WorkItem.cpp + + + + + POSIX + + + delay.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\delay\delay.c + + + pthread.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread.c + + + pthread_attr.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_attr.c + + + pthread_barrier.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_barrier.c + + + pthread_cond.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_cond.c + + + pthread_mutex.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_mutex.c + + + pthread_rwlock.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_rwlock.c + + + pthread_spin.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_spin.c + + + pthread_tls.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\pthread_tls.c + + + sched.c + 1 + ..\..\..\rtos\rt-thread\components\libc\posix\pthreads\sched.c + + + + + rtt/Drivers + + + drv_usart.c + 1 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_usart.c + + + drv_common.c + 1 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_common.c + + + drv_gpio.c + 1 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_gpio.c + + + drv_spi.c + 1 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_spi.c + + + drv_adc.c + 1 + ..\..\..\rtos\platform\stm32\HAL_Drivers\drv_adc.c + + + + + utest + + + test_thread.cpp + 8 + ..\..\..\apps\utest\test_thread\test_thread.cpp + + + test_uorb_main.cpp + 8 + ..\..\..\apps\utest\test_uorb\test_uorb_main.cpp + + + + + Utilities + + + ulog.c + 1 + ..\..\..\rtos\rt-thread\components\utilities\ulog\ulog.c + + + console_be.c + 1 + ..\..\..\rtos\rt-thread\components\utilities\ulog\backend\console_be.c + + + file_be.c + 1 + ..\..\..\rtos\rt-thread\components\utilities\ulog\backend\file_be.c diff --git a/bsps/px4/fmu-v5/rtconfig.h b/bsps/px4/fmu-v5/rtconfig.h index 798fc9f164..1c9e38664a 100644 --- a/bsps/px4/fmu-v5/rtconfig.h +++ b/bsps/px4/fmu-v5/rtconfig.h @@ -472,6 +472,12 @@ /* Nextpilot Telemetry Config */ /* end of Nextpilot Telemetry Config */ + +/* NextPilot Test Config */ + +#define TEST_CREATE_THREAD +#define TEST_UORB +/* end of NextPilot Test Config */ /* end of Nextpilot Firmware Config */ /* Nextpilot Packages Config */ diff --git a/bsps/sitl/qemu/config/mc_manual.config b/bsps/sitl/qemu/config/mc_manual.config index 3876214a5e..5596a4d95e 100644 --- a/bsps/sitl/qemu/config/mc_manual.config +++ b/bsps/sitl/qemu/config/mc_manual.config @@ -35,7 +35,7 @@ CONFIG_RT_KPRINTF_USING_LONGLONG=y CONFIG_RT_USING_DEBUG=y CONFIG_RT_DEBUGING_COLOR=y CONFIG_RT_DEBUGING_CONTEXT=y -CONFIG_RT_DEBUGING_INIT=y +# CONFIG_RT_DEBUGING_INIT is not set # CONFIG_RT_DEBUGING_PAGE_LEAK is not set # diff --git a/bsps/sitl/qemu/rtconfig.h b/bsps/sitl/qemu/rtconfig.h index cc1c1332d8..161fb0f9cc 100644 --- a/bsps/sitl/qemu/rtconfig.h +++ b/bsps/sitl/qemu/rtconfig.h @@ -25,6 +25,7 @@ #define RT_USING_DEBUG #define RT_DEBUGING_COLOR #define RT_DEBUGING_CONTEXT +#define RT_DEBUGING_INIT /* Inter-Thread communication */ diff --git a/pkgs/param/module_params.c b/pkgs/param/module_params.c index 08a181da2a..216bc3065f 100644 --- a/pkgs/param/module_params.c +++ b/pkgs/param/module_params.c @@ -1,9329 +1,8945 @@ /** - * MAVLink Config for instance 0 - * - * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance - * - * - * @group MAVLink - * @value 0 Disabled - * @value 1 Uart1 - * @value 2 Uart2 - * @value 3 Uart3 - * @value 4 Uart4 - * @value 5 Uart5 - * @value 6 Uart6 - * @value 7 Uart7 - * @value 8 Uart8 - * @value 20 UBS1 - * @value 21 USB2 - * @value 30 UDP - * @value 31 TCP - * @reboot_required True - */ -PARAM_DEFINE_INT32(MAV_0_CONFIG, 0); - -/** - * MAVLink Config for instance 1 - * - * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance - * - * - * @group MAVLink - * @value 0 Disabled - * @value 1 Uart1 - * @value 2 Uart2 - * @value 3 Uart3 - * @value 4 Uart4 - * @value 5 Uart5 - * @value 6 Uart6 - * @value 7 Uart7 - * @value 8 Uart8 - * @value 20 UBS1 - * @value 21 USB2 - * @value 30 UDP - * @value 31 TCP - * @reboot_required True - */ -PARAM_DEFINE_INT32(MAV_1_CONFIG, 0); - -/** - * MAVLink Config for instance 2 + * Accelerometer 0 calibration device ID * - * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance - * + * Device ID of the accelerometer this calibration applies to. * - * @group MAVLink - * @value 0 Disabled - * @value 1 Uart1 - * @value 2 Uart2 - * @value 3 Uart3 - * @value 4 Uart4 - * @value 5 Uart5 - * @value 6 Uart6 - * @value 7 Uart7 - * @value 8 Uart8 - * @value 20 UBS1 - * @value 21 USB2 - * @value 30 UDP - * @value 31 TCP - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System */ -PARAM_DEFINE_INT32(MAV_2_CONFIG, 0); +PARAM_DEFINE_INT32(CAL_ACC0_ID, 0); /** - * MAVLink Mode for instance 0 + * Accelerometer 1 calibration device ID * - * The MAVLink Mode defines the set of streamed messages (for example the - * vehicle's attitude) and their sending rates. - * + * Device ID of the accelerometer this calibration applies to. * - * @group MAVLink - * @value 0 Normal - * @value 1 Custom - * @value 2 Onboard - * @value 3 OSD - * @value 4 Magic - * @value 5 Config - * @value 7 Minimal - * @value 8 External Vision - * @value 10 Gimbal - * @value 11 Onboard Low Bandwidth - * @value 12 uAvionix - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System */ -PARAM_DEFINE_INT32(MAV_0_MODE, 0); +PARAM_DEFINE_INT32(CAL_ACC1_ID, 0); /** - * MAVLink Mode for instance 1 + * Accelerometer 2 calibration device ID * - * The MAVLink Mode defines the set of streamed messages (for example the - * vehicle's attitude) and their sending rates. - * + * Device ID of the accelerometer this calibration applies to. * - * @group MAVLink - * @value 0 Normal - * @value 1 Custom - * @value 2 Onboard - * @value 3 OSD - * @value 4 Magic - * @value 5 Config - * @value 7 Minimal - * @value 8 External Vision - * @value 10 Gimbal - * @value 11 Onboard Low Bandwidth - * @value 12 uAvionix - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System */ -PARAM_DEFINE_INT32(MAV_1_MODE, 2); +PARAM_DEFINE_INT32(CAL_ACC2_ID, 0); /** - * MAVLink Mode for instance 2 + * Accelerometer 3 calibration device ID * - * The MAVLink Mode defines the set of streamed messages (for example the - * vehicle's attitude) and their sending rates. - * + * Device ID of the accelerometer this calibration applies to. * - * @group MAVLink - * @value 0 Normal - * @value 1 Custom - * @value 2 Onboard - * @value 3 OSD - * @value 4 Magic - * @value 5 Config - * @value 7 Minimal - * @value 8 External Vision - * @value 10 Gimbal - * @value 11 Onboard Low Bandwidth - * @value 12 uAvionix - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System */ -PARAM_DEFINE_INT32(MAV_2_MODE, 0); +PARAM_DEFINE_INT32(CAL_ACC3_ID, 0); /** - * Maximum MAVLink sending rate for instance 0 + * Accelerometer 0 priority * - * Configure the maximum sending rate for the MAVLink streams in Bytes/sec. - * If the configured streams exceed the maximum rate, the sending rate of - * each stream is automatically decreased. - * - * If this is set to 0 a value of half of the theoretical maximum bandwidth is used. - * This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on - * 8N1-configured links). * * - * @group MAVLink - * @min 0 - * @unit B/s - * @reboot_required True + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @decimal 3 + * @category System */ -PARAM_DEFINE_INT32(MAV_0_RATE, 1200); +PARAM_DEFINE_INT32(CAL_ACC0_PRIO, -1); /** - * Maximum MAVLink sending rate for instance 1 + * Accelerometer 1 priority * - * Configure the maximum sending rate for the MAVLink streams in Bytes/sec. - * If the configured streams exceed the maximum rate, the sending rate of - * each stream is automatically decreased. - * - * If this is set to 0 a value of half of the theoretical maximum bandwidth is used. - * This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on - * 8N1-configured links). * * - * @group MAVLink - * @min 0 - * @unit B/s - * @reboot_required True + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @decimal 3 + * @category System */ -PARAM_DEFINE_INT32(MAV_1_RATE, 0); +PARAM_DEFINE_INT32(CAL_ACC1_PRIO, -1); /** - * Maximum MAVLink sending rate for instance 2 + * Accelerometer 2 priority * - * Configure the maximum sending rate for the MAVLink streams in Bytes/sec. - * If the configured streams exceed the maximum rate, the sending rate of - * each stream is automatically decreased. - * - * If this is set to 0 a value of half of the theoretical maximum bandwidth is used. - * This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on - * 8N1-configured links). * * - * @group MAVLink - * @min 0 - * @unit B/s - * @reboot_required True + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @decimal 3 + * @category System */ -PARAM_DEFINE_INT32(MAV_2_RATE, 0); +PARAM_DEFINE_INT32(CAL_ACC2_PRIO, -1); /** - * Enable MAVLink Message forwarding for instance 0 + * Accelerometer 3 priority * - * If enabled, forward incoming MAVLink messages to other MAVLink ports if the - * message is either broadcast or the target is not the autopilot. - * - * This allows for example a GCS to talk to a camera that is connected to the - * autopilot via MAVLink (on a different link than the GCS). * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @decimal 3 + * @category System */ -PARAM_DEFINE_INT32(MAV_0_FORWARD, 1); +PARAM_DEFINE_INT32(CAL_ACC3_PRIO, -1); /** - * Enable MAVLink Message forwarding for instance 1 + * Accelerometer 0 rotation relative to airframe * - * If enabled, forward incoming MAVLink messages to other MAVLink ports if the - * message is either broadcast or the target is not the autopilot. - * - * This allows for example a GCS to talk to a camera that is connected to the - * autopilot via MAVLink (on a different link than the GCS). + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group MAVLink - * @boolean - * @reboot_required True - */ -PARAM_DEFINE_INT32(MAV_1_FORWARD, 0); - + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 + */ +PARAM_DEFINE_INT32(CAL_ACC0_ROT, -1); + /** - * Enable MAVLink Message forwarding for instance 2 + * Accelerometer 1 rotation relative to airframe * - * If enabled, forward incoming MAVLink messages to other MAVLink ports if the - * message is either broadcast or the target is not the autopilot. - * - * This allows for example a GCS to talk to a camera that is connected to the - * autopilot via MAVLink (on a different link than the GCS). + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(MAV_2_FORWARD, 0); +PARAM_DEFINE_INT32(CAL_ACC1_ROT, -1); /** - * Enable software throttling of mavlink on instance 0 + * Accelerometer 2 rotation relative to airframe * - * If enabled, MAVLink messages will be throttled according to - * `txbuf` field reported by radio_status. - * - * Requires a radio to send the mavlink message RADIO_STATUS. + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(MAV_0_RADIO_CTL, 1); +PARAM_DEFINE_INT32(CAL_ACC2_ROT, -1); /** - * Enable software throttling of mavlink on instance 1 + * Accelerometer 3 rotation relative to airframe * - * If enabled, MAVLink messages will be throttled according to - * `txbuf` field reported by radio_status. - * - * Requires a radio to send the mavlink message RADIO_STATUS. + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(MAV_1_RADIO_CTL, 1); +PARAM_DEFINE_INT32(CAL_ACC3_ROT, -1); /** - * Enable software throttling of mavlink on instance 2 + * Accelerometer 0 X-axis offset * - * If enabled, MAVLink messages will be throttled according to - * `txbuf` field reported by radio_status. - * - * Requires a radio to send the mavlink message RADIO_STATUS. * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_INT32(MAV_2_RADIO_CTL, 1); +PARAM_DEFINE_FLOAT(CAL_ACC0_XOFF, 0.0); /** - * Enable serial flow control for instance 0 + * Accelerometer 1 X-axis offset * - * This is used to force flow control on or off for the the mavlink - * instance. By default it is auto detected. Use when auto detection fails. * * - * @group MAVLink - * @value 0 Force off - * @value 1 Force on - * @value 2 Auto-detected - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_INT32(MAV_0_FLOW_CTRL, 2); +PARAM_DEFINE_FLOAT(CAL_ACC1_XOFF, 0.0); /** - * Enable serial flow control for instance 1 + * Accelerometer 2 X-axis offset * - * This is used to force flow control on or off for the the mavlink - * instance. By default it is auto detected. Use when auto detection fails. * * - * @group MAVLink - * @value 0 Force off - * @value 1 Force on - * @value 2 Auto-detected - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_INT32(MAV_1_FLOW_CTRL, 2); +PARAM_DEFINE_FLOAT(CAL_ACC2_XOFF, 0.0); /** - * Enable serial flow control for instance 2 + * Accelerometer 3 X-axis offset * - * This is used to force flow control on or off for the the mavlink - * instance. By default it is auto detected. Use when auto detection fails. * * - * @group MAVLink - * @value 0 Force off - * @value 1 Force on - * @value 2 Auto-detected - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_INT32(MAV_2_FLOW_CTRL, 2); +PARAM_DEFINE_FLOAT(CAL_ACC3_XOFF, 0.0); /** - * Empty cell voltage (5C load) + * Accelerometer 0 Y-axis offset * - * Defines the voltage where a single cell of battery 1 is considered empty. - * The voltage should be chosen before the steep dropoff to 2.8V. A typical - * lithium battery can only be discharged down to 10% before it drops off - * to a voltage level damaging the cells. * * - * @group Battery Calibration - * @decimal 2 - * @increment 0.01 - * @unit V - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(BAT1_V_EMPTY, 3.6); +PARAM_DEFINE_FLOAT(CAL_ACC0_YOFF, 0.0); /** - * Empty cell voltage (5C load) + * Accelerometer 1 Y-axis offset * - * Defines the voltage where a single cell of battery 1 is considered empty. - * The voltage should be chosen before the steep dropoff to 2.8V. A typical - * lithium battery can only be discharged down to 10% before it drops off - * to a voltage level damaging the cells. * * - * @group Battery Calibration - * @decimal 2 - * @increment 0.01 - * @unit V - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(BAT2_V_EMPTY, 3.6); +PARAM_DEFINE_FLOAT(CAL_ACC1_YOFF, 0.0); /** - * Full cell voltage (5C load) + * Accelerometer 2 Y-axis offset * - * Defines the voltage where a single cell of battery 1 is considered full - * under a mild load. This will never be the nominal voltage of 4.2V * * - * @group Battery Calibration - * @decimal 2 - * @increment 0.01 - * @unit V - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(BAT1_V_CHARGED, 4.05); +PARAM_DEFINE_FLOAT(CAL_ACC2_YOFF, 0.0); /** - * Full cell voltage (5C load) + * Accelerometer 3 Y-axis offset * - * Defines the voltage where a single cell of battery 1 is considered full - * under a mild load. This will never be the nominal voltage of 4.2V * * - * @group Battery Calibration - * @decimal 2 - * @increment 0.01 - * @unit V - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(BAT2_V_CHARGED, 4.05); +PARAM_DEFINE_FLOAT(CAL_ACC3_YOFF, 0.0); /** - * Voltage drop per cell on full throttle + * Accelerometer 0 Z-axis offset * - * This implicitly defines the internal resistance - * to maximum current ratio for battery 1 and assumes linearity. - * A good value to use is the difference between the - * 5C and 20-25C load. Not used if BAT1_R_INTERNAL is - * set. * * - * @group Battery Calibration - * @decimal 2 - * @increment 0.01 - * @min 0.07 - * @max 0.5 - * @unit V - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(BAT1_V_LOAD_DROP, 0.1); +PARAM_DEFINE_FLOAT(CAL_ACC0_ZOFF, 0.0); /** - * Voltage drop per cell on full throttle + * Accelerometer 1 Z-axis offset * - * This implicitly defines the internal resistance - * to maximum current ratio for battery 1 and assumes linearity. - * A good value to use is the difference between the - * 5C and 20-25C load. Not used if BAT2_R_INTERNAL is - * set. * * - * @group Battery Calibration - * @decimal 2 - * @increment 0.01 - * @min 0.07 - * @max 0.5 - * @unit V - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(BAT2_V_LOAD_DROP, 0.1); +PARAM_DEFINE_FLOAT(CAL_ACC1_ZOFF, 0.0); /** - * Explicitly defines the per cell internal resistance for battery 1 + * Accelerometer 2 Z-axis offset * - * If non-negative, then this will be used in place of - * BAT1_V_LOAD_DROP for all calculations. * * - * @group Battery Calibration - * @decimal 4 - * @increment 0.0005 - * @min -1.0 - * @max 0.2 - * @unit Ohm - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(BAT1_R_INTERNAL, 0.005); +PARAM_DEFINE_FLOAT(CAL_ACC2_ZOFF, 0.0); /** - * Explicitly defines the per cell internal resistance for battery 2 + * Accelerometer 3 Z-axis offset * - * If non-negative, then this will be used in place of - * BAT2_V_LOAD_DROP for all calculations. * * - * @group Battery Calibration - * @decimal 4 - * @increment 0.0005 - * @min -1.0 - * @max 0.2 - * @unit Ohm - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(BAT2_R_INTERNAL, 0.005); +PARAM_DEFINE_FLOAT(CAL_ACC3_ZOFF, 0.0); /** - * Number of cells for battery 1. + * Accelerometer 0 X-axis scaling factor * - * Defines the number of cells the attached battery consists of. * * - * @group Battery Calibration - * @value 1 1S Battery - * @value 2 2S Battery - * @value 3 3S Battery - * @value 4 4S Battery - * @value 5 5S Battery - * @value 6 6S Battery - * @value 7 7S Battery - * @value 8 8S Battery - * @value 9 9S Battery - * @value 10 10S Battery - * @value 11 11S Battery - * @value 12 12S Battery - * @value 13 13S Battery - * @value 14 14S Battery - * @value 15 15S Battery - * @value 16 16S Battery - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(BAT1_N_CELLS, 0); +PARAM_DEFINE_FLOAT(CAL_ACC0_XSCALE, 1.0); /** - * Number of cells for battery 2. + * Accelerometer 1 X-axis scaling factor * - * Defines the number of cells the attached battery consists of. * * - * @group Battery Calibration - * @value 1 1S Battery - * @value 2 2S Battery - * @value 3 3S Battery - * @value 4 4S Battery - * @value 5 5S Battery - * @value 6 6S Battery - * @value 7 7S Battery - * @value 8 8S Battery - * @value 9 9S Battery - * @value 10 10S Battery - * @value 11 11S Battery - * @value 12 12S Battery - * @value 13 13S Battery - * @value 14 14S Battery - * @value 15 15S Battery - * @value 16 16S Battery - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(BAT2_N_CELLS, 0); +PARAM_DEFINE_FLOAT(CAL_ACC1_XSCALE, 1.0); /** - * Battery 1 capacity. + * Accelerometer 2 X-axis scaling factor * - * Defines the capacity of battery 1 in mAh. * * - * @group Battery Calibration - * @decimal 0 - * @increment 50 - * @min -1.0 - * @max 100000 - * @unit mAh - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(BAT1_CAPACITY, -1.0); +PARAM_DEFINE_FLOAT(CAL_ACC2_XSCALE, 1.0); /** - * Battery 2 capacity. + * Accelerometer 3 X-axis scaling factor * - * Defines the capacity of battery 2 in mAh. * * - * @group Battery Calibration - * @decimal 0 - * @increment 50 - * @min -1.0 - * @max 100000 - * @unit mAh - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(BAT2_CAPACITY, -1.0); +PARAM_DEFINE_FLOAT(CAL_ACC3_XSCALE, 1.0); /** - * Battery 1 monitoring source. + * Accelerometer 0 Y-axis scaling factor * - * This parameter controls the source of battery data. The value 'Power Module' - * means that measurements are expected to come from a power module. If the value is set to - * 'External' then the system expects to receive mavlink battery status messages. - * If the value is set to 'ESCs', the battery information are taken from the esc_status message. - * This requires the ESC to provide both voltage as well as current. * * - * @group Battery Calibration - * @value -1 Disabled - * @value 0 Power Module - * @value 1 External - * @value 2 ESCs - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(BAT1_SOURCE, 0); +PARAM_DEFINE_FLOAT(CAL_ACC0_YSCALE, 1.0); /** - * Battery 2 monitoring source. + * Accelerometer 1 Y-axis scaling factor * - * This parameter controls the source of battery data. The value 'Power Module' - * means that measurements are expected to come from a power module. If the value is set to - * 'External' then the system expects to receive mavlink battery status messages. - * If the value is set to 'ESCs', the battery information are taken from the esc_status message. - * This requires the ESC to provide both voltage as well as current. * * - * @group Battery Calibration - * @value -1 Disabled - * @value 0 Power Module - * @value 1 External - * @value 2 ESCs - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(BAT2_SOURCE, -1); +PARAM_DEFINE_FLOAT(CAL_ACC1_YSCALE, 1.0); /** - * Battery 1 voltage divider (V divider) + * Accelerometer 2 Y-axis scaling factor * - * This is the divider from battery 1 voltage to ADC voltage. - * If using e.g. Mauch power modules the value from the datasheet - * can be applied straight here. A value of -1 means to use - * the board default. * * - * @group Battery Calibration - * @decimal 8 - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(BAT1_V_DIV, -1.0); +PARAM_DEFINE_FLOAT(CAL_ACC2_YSCALE, 1.0); /** - * Battery 2 voltage divider (V divider) + * Accelerometer 3 Y-axis scaling factor * - * This is the divider from battery 2 voltage to ADC voltage. - * If using e.g. Mauch power modules the value from the datasheet - * can be applied straight here. A value of -1 means to use - * the board default. * * - * @group Battery Calibration - * @decimal 8 - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(BAT2_V_DIV, -1.0); +PARAM_DEFINE_FLOAT(CAL_ACC3_YSCALE, 1.0); /** - * Battery 1 current per volt (A/V) + * Accelerometer 0 Z-axis scaling factor * - * The voltage seen by the ADC multiplied by this factor - * will determine the battery current. A value of -1 means to use - * the board default. * * - * @group Battery Calibration - * @decimal 8 - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(BAT1_A_PER_V, -1.0); +PARAM_DEFINE_FLOAT(CAL_ACC0_ZSCALE, 1.0); /** - * Battery 2 current per volt (A/V) + * Accelerometer 1 Z-axis scaling factor * - * The voltage seen by the ADC multiplied by this factor - * will determine the battery current. A value of -1 means to use - * the board default. * * - * @group Battery Calibration - * @decimal 8 - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(BAT2_A_PER_V, -1.0); +PARAM_DEFINE_FLOAT(CAL_ACC1_ZSCALE, 1.0); /** - * Battery 1 Voltage ADC Channel + * Accelerometer 2 Z-axis scaling factor * - * This parameter specifies the ADC channel used to monitor voltage of main power battery. - * A value of -1 means to use the board default. * * - * @group Battery Calibration - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(BAT1_V_CHANNEL, -1); +PARAM_DEFINE_FLOAT(CAL_ACC2_ZSCALE, 1.0); /** - * Battery 2 Voltage ADC Channel + * Accelerometer 3 Z-axis scaling factor * - * This parameter specifies the ADC channel used to monitor voltage of main power battery. - * A value of -1 means to use the board default. * * - * @group Battery Calibration - * @reboot_required True + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(BAT2_V_CHANNEL, -1); +PARAM_DEFINE_FLOAT(CAL_ACC3_ZSCALE, 1.0); /** - * Battery 1 Current ADC Channel + * Barometer 0 calibration device ID * - * This parameter specifies the ADC channel used to monitor current of main power battery. - * A value of -1 means to use the board default. - * + * Device ID of the barometer this calibration applies to. * - * @group Battery Calibration - * @reboot_required True + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(BAT1_I_CHANNEL, -1); +PARAM_DEFINE_INT32(CAL_BARO0_ID, 0); /** - * Battery 2 Current ADC Channel + * Barometer 1 calibration device ID * - * This parameter specifies the ADC channel used to monitor current of main power battery. - * A value of -1 means to use the board default. - * + * Device ID of the barometer this calibration applies to. * - * @group Battery Calibration - * @reboot_required True + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(BAT2_I_CHANNEL, -1); +PARAM_DEFINE_INT32(CAL_BARO1_ID, 0); /** - * SIM_GZ ESC 1 Output Function + * Barometer 2 calibration device ID * - * Select what should be output on SIM_GZ ESC 1. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest - * + * Device ID of the barometer this calibration applies to. * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC1, 0); +PARAM_DEFINE_INT32(CAL_BARO2_ID, 0); /** - * SIM_GZ ESC 2 Output Function + * Barometer 3 calibration device ID * - * Select what should be output on SIM_GZ ESC 2. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest - * + * Device ID of the barometer this calibration applies to. * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC2, 0); +PARAM_DEFINE_INT32(CAL_BARO3_ID, 0); /** - * SIM_GZ ESC 3 Output Function + * Barometer 0 priority * - * Select what should be output on SIM_GZ ESC 3. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest * * - * @group Actuator Outputs + * @group Sensor Calibration + * @value -1 Uninitialized * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC3, 0); +PARAM_DEFINE_INT32(CAL_BARO0_PRIO, -1); /** - * SIM_GZ ESC 4 Output Function + * Barometer 1 priority * - * Select what should be output on SIM_GZ ESC 4. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest * * - * @group Actuator Outputs + * @group Sensor Calibration + * @value -1 Uninitialized * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC4, 0); +PARAM_DEFINE_INT32(CAL_BARO1_PRIO, -1); /** - * SIM_GZ ESC 5 Output Function + * Barometer 2 priority * - * Select what should be output on SIM_GZ ESC 5. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest * * - * @group Actuator Outputs + * @group Sensor Calibration + * @value -1 Uninitialized * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC5, 0); +PARAM_DEFINE_INT32(CAL_BARO2_PRIO, -1); /** - * SIM_GZ ESC 6 Output Function + * Barometer 3 priority * - * Select what should be output on SIM_GZ ESC 6. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest * * - * @group Actuator Outputs + * @group Sensor Calibration + * @value -1 Uninitialized * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC6, 0); +PARAM_DEFINE_INT32(CAL_BARO3_PRIO, -1); /** - * SIM_GZ ESC 7 Output Function + * Barometer 0 offset * - * Select what should be output on SIM_GZ ESC 7. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC7, 0); +PARAM_DEFINE_FLOAT(CAL_BARO0_OFF, 0.0); /** - * SIM_GZ ESC 8 Output Function + * Barometer 1 offset * - * Select what should be output on SIM_GZ ESC 8. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC8, 0); +PARAM_DEFINE_FLOAT(CAL_BARO1_OFF, 0.0); /** - * SIM_GZ ESC 1 Disarmed Value + * Barometer 2 offset * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS1, 0); +PARAM_DEFINE_FLOAT(CAL_BARO2_OFF, 0.0); /** - * SIM_GZ ESC 2 Disarmed Value + * Barometer 3 offset * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS2, 0); +PARAM_DEFINE_FLOAT(CAL_BARO3_OFF, 0.0); /** - * SIM_GZ ESC 3 Disarmed Value + * Gyroscope 0 calibration device ID * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * + * Device ID of the gyroscope this calibration applies to. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS3, 0); +PARAM_DEFINE_INT32(CAL_GYRO0_ID, 0); /** - * SIM_GZ ESC 4 Disarmed Value + * Gyroscope 1 calibration device ID * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * + * Device ID of the gyroscope this calibration applies to. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS4, 0); +PARAM_DEFINE_INT32(CAL_GYRO1_ID, 0); /** - * SIM_GZ ESC 5 Disarmed Value + * Gyroscope 2 calibration device ID * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * + * Device ID of the gyroscope this calibration applies to. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS5, 0); +PARAM_DEFINE_INT32(CAL_GYRO2_ID, 0); /** - * SIM_GZ ESC 6 Disarmed Value + * Gyroscope 3 calibration device ID * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * + * Device ID of the gyroscope this calibration applies to. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS6, 0); +PARAM_DEFINE_INT32(CAL_GYRO3_ID, 0); /** - * SIM_GZ ESC 7 Disarmed Value + * Gyroscope 0 priority * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS7, 0); +PARAM_DEFINE_INT32(CAL_GYRO0_PRIO, -1); /** - * SIM_GZ ESC 8 Disarmed Value + * Gyroscope 1 priority * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS8, 0); +PARAM_DEFINE_INT32(CAL_GYRO1_PRIO, -1); /** - * SIM_GZ ESC 1 Minimum Value + * Gyroscope 2 priority * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN1, 0); +PARAM_DEFINE_INT32(CAL_GYRO2_PRIO, -1); /** - * SIM_GZ ESC 2 Minimum Value + * Gyroscope 3 priority * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN2, 0); +PARAM_DEFINE_INT32(CAL_GYRO3_PRIO, -1); /** - * SIM_GZ ESC 3 Minimum Value + * Gyroscope 0 rotation relative to airframe * - * Minimum output value (when not disarmed). + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN3, 0); +PARAM_DEFINE_INT32(CAL_GYRO0_ROT, -1); /** - * SIM_GZ ESC 4 Minimum Value + * Gyroscope 1 rotation relative to airframe * - * Minimum output value (when not disarmed). + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN4, 0); +PARAM_DEFINE_INT32(CAL_GYRO1_ROT, -1); /** - * SIM_GZ ESC 5 Minimum Value + * Gyroscope 2 rotation relative to airframe * - * Minimum output value (when not disarmed). + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN5, 0); +PARAM_DEFINE_INT32(CAL_GYRO2_ROT, -1); /** - * SIM_GZ ESC 6 Minimum Value + * Gyroscope 3 rotation relative to airframe * - * Minimum output value (when not disarmed). + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN6, 0); +PARAM_DEFINE_INT32(CAL_GYRO3_ROT, -1); /** - * SIM_GZ ESC 7 Minimum Value + * Gyroscope 0 X-axis offset * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN7, 0); +PARAM_DEFINE_FLOAT(CAL_GYRO0_XOFF, 0.0); /** - * SIM_GZ ESC 8 Minimum Value + * Gyroscope 1 X-axis offset * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN8, 0); +PARAM_DEFINE_FLOAT(CAL_GYRO1_XOFF, 0.0); /** - * SIM_GZ ESC 1 Maximum Value + * Gyroscope 2 X-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX1, 1000); +PARAM_DEFINE_FLOAT(CAL_GYRO2_XOFF, 0.0); /** - * SIM_GZ ESC 2 Maximum Value + * Gyroscope 3 X-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX2, 1000); +PARAM_DEFINE_FLOAT(CAL_GYRO3_XOFF, 0.0); /** - * SIM_GZ ESC 3 Maximum Value + * Gyroscope 0 Y-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX3, 1000); +PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0); /** - * SIM_GZ ESC 4 Maximum Value + * Gyroscope 1 Y-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX4, 1000); +PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0); /** - * SIM_GZ ESC 5 Maximum Value + * Gyroscope 2 Y-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX5, 1000); +PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0); /** - * SIM_GZ ESC 6 Maximum Value + * Gyroscope 3 Y-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX6, 1000); +PARAM_DEFINE_FLOAT(CAL_GYRO3_YOFF, 0.0); /** - * SIM_GZ ESC 7 Maximum Value + * Gyroscope 0 Z-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX7, 1000); +PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0); /** - * SIM_GZ ESC 8 Maximum Value + * Gyroscope 1 Z-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX8, 1000); +PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0); /** - * SIM_GZ ESC 1 Failsafe Value + * Gyroscope 2 Z-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC1). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL1, -1); +PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0); /** - * SIM_GZ ESC 2 Failsafe Value + * Gyroscope 3 Z-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC2). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit rad/s */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL2, -1); +PARAM_DEFINE_FLOAT(CAL_GYRO3_ZOFF, 0.0); /** - * SIM_GZ ESC 3 Failsafe Value + * Magnetometer 0 calibration device ID * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC3). - * + * Device ID of the magnetometer this calibration applies to. * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL3, -1); +PARAM_DEFINE_INT32(CAL_MAG0_ID, 0); /** - * SIM_GZ ESC 4 Failsafe Value + * Magnetometer 1 calibration device ID * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC4). - * + * Device ID of the magnetometer this calibration applies to. * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL4, -1); +PARAM_DEFINE_INT32(CAL_MAG1_ID, 0); /** - * SIM_GZ ESC 5 Failsafe Value + * Magnetometer 2 calibration device ID * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC5). - * + * Device ID of the magnetometer this calibration applies to. * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL5, -1); +PARAM_DEFINE_INT32(CAL_MAG2_ID, 0); /** - * SIM_GZ ESC 6 Failsafe Value + * Magnetometer 3 calibration device ID * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC6). - * + * Device ID of the magnetometer this calibration applies to. * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL6, -1); +PARAM_DEFINE_INT32(CAL_MAG3_ID, 0); /** - * SIM_GZ ESC 7 Failsafe Value + * Magnetometer 0 priority * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC7). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL7, -1); +PARAM_DEFINE_INT32(CAL_MAG0_PRIO, -1); /** - * SIM_GZ ESC 8 Failsafe Value + * Magnetometer 1 priority * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC8). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL8, -1); +PARAM_DEFINE_INT32(CAL_MAG1_PRIO, -1); /** - * SIM_GZ Servo 1 Output Function + * Magnetometer 2 priority * - * Select what should be output on SIM_GZ Servo 1. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest * * - * @group Actuator Outputs + * @group Sensor Calibration + * @value -1 Uninitialized * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC1, 0); +PARAM_DEFINE_INT32(CAL_MAG2_PRIO, -1); /** - * SIM_GZ Servo 2 Output Function + * Magnetometer 3 priority * - * Select what should be output on SIM_GZ Servo 2. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest * * - * @group Actuator Outputs + * @group Sensor Calibration + * @value -1 Uninitialized * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max + * @category System */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC2, 0); +PARAM_DEFINE_INT32(CAL_MAG3_PRIO, -1); /** - * SIM_GZ Servo 3 Output Function + * Magnetometer 0 rotation relative to airframe * - * Select what should be output on SIM_GZ Servo 3. + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 + */ +PARAM_DEFINE_INT32(CAL_MAG0_ROT, -1); + +/** + * Magnetometer 1 rotation relative to airframe + * + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC3, 0); - -/** - * SIM_GZ Servo 4 Output Function - * - * Select what should be output on SIM_GZ Servo 4. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest - * - * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC4, 0); - -/** - * SIM_GZ Servo 5 Output Function - * - * Select what should be output on SIM_GZ Servo 5. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest - * - * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC5, 0); - -/** - * SIM_GZ Servo 6 Output Function - * - * Select what should be output on SIM_GZ Servo 6. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest - * - * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC6, 0); - -/** - * SIM_GZ Servo 7 Output Function - * - * Select what should be output on SIM_GZ Servo 7. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest - * - * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC7, 0); - -/** - * SIM_GZ Servo 8 Output Function - * - * Select what should be output on SIM_GZ Servo 8. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest - * - * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC8, 0); - -/** - * SIM_GZ Servo 1 Disarmed Value - * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS1, 500); - -/** - * SIM_GZ Servo 2 Disarmed Value - * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS2, 500); - -/** - * SIM_GZ Servo 3 Disarmed Value - * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS3, 500); - -/** - * SIM_GZ Servo 4 Disarmed Value - * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS4, 500); - -/** - * SIM_GZ Servo 5 Disarmed Value - * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS5, 500); - -/** - * SIM_GZ Servo 6 Disarmed Value - * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS6, 500); - -/** - * SIM_GZ Servo 7 Disarmed Value - * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS7, 500); - -/** - * SIM_GZ Servo 8 Disarmed Value - * - * This is the output value that is set when not armed. - * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS8, 500); - -/** - * SIM_GZ Servo 1 Minimum Value - * - * Minimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN1, 0); - -/** - * SIM_GZ Servo 2 Minimum Value - * - * Minimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN2, 0); - -/** - * SIM_GZ Servo 3 Minimum Value - * - * Minimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN3, 0); - -/** - * SIM_GZ Servo 4 Minimum Value - * - * Minimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN4, 0); - -/** - * SIM_GZ Servo 5 Minimum Value - * - * Minimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN5, 0); - -/** - * SIM_GZ Servo 6 Minimum Value - * - * Minimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN6, 0); - -/** - * SIM_GZ Servo 7 Minimum Value - * - * Minimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN7, 0); - -/** - * SIM_GZ Servo 8 Minimum Value - * - * Minimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN8, 0); - -/** - * SIM_GZ Servo 1 Maximum Value - * - * Maxmimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 - */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX1, 1000); - -/** - * SIM_GZ Servo 2 Maximum Value - * - * Maxmimum output value (when not disarmed). - * - * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX2, 1000); +PARAM_DEFINE_INT32(CAL_MAG1_ROT, -1); /** - * SIM_GZ Servo 3 Maximum Value + * Magnetometer 2 rotation relative to airframe * - * Maxmimum output value (when not disarmed). + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX3, 1000); +PARAM_DEFINE_INT32(CAL_MAG2_ROT, -1); /** - * SIM_GZ Servo 4 Maximum Value + * Magnetometer 3 rotation relative to airframe * - * Maxmimum output value (when not disarmed). + * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @value -1 Internal + * @value 0 No rotation + * @value 1 Yaw 45° + * @value 2 Yaw 90° + * @value 3 Yaw 135° + * @value 4 Yaw 180° + * @value 5 Yaw 225° + * @value 6 Yaw 270° + * @value 7 Yaw 315° + * @value 8 Roll 180° + * @value 9 Roll 180°, Yaw 45° + * @value 10 Roll 180°, Yaw 90° + * @value 11 Roll 180°, Yaw 135° + * @value 12 Pitch 180° + * @value 13 Roll 180°, Yaw 225° + * @value 14 Roll 180°, Yaw 270° + * @value 15 Roll 180°, Yaw 315° + * @value 16 Roll 90° + * @value 17 Roll 90°, Yaw 45° + * @value 18 Roll 90°, Yaw 90° + * @value 19 Roll 90°, Yaw 135° + * @value 20 Roll 270° + * @value 21 Roll 270°, Yaw 45° + * @value 22 Roll 270°, Yaw 90° + * @value 23 Roll 270°, Yaw 135° + * @value 24 Pitch 90° + * @value 25 Pitch 270° + * @value 26 Pitch 180°, Yaw 90° + * @value 27 Pitch 180°, Yaw 270° + * @value 28 Roll 90°, Pitch 90° + * @value 29 Roll 180°, Pitch 90° + * @value 30 Roll 270°, Pitch 90° + * @value 31 Roll 90°, Pitch 180° + * @value 32 Roll 270°, Pitch 180° + * @value 33 Roll 90°, Pitch 270° + * @value 34 Roll 180°, Pitch 270° + * @value 35 Roll 270°, Pitch 270° + * @value 36 Roll 90°, Pitch 180°, Yaw 90° + * @value 37 Roll 90°, Yaw 270° + * @value 38 Roll 90°, Pitch 68°, Yaw 293° + * @value 39 Pitch 315° + * @value 40 Roll 90°, Pitch 315° + * @category System + * @min -1 + * @max 40 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX4, 1000); +PARAM_DEFINE_INT32(CAL_MAG3_ROT, -1); /** - * SIM_GZ Servo 5 Maximum Value + * Magnetometer 0 X-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX5, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG0_XOFF, 0.0); /** - * SIM_GZ Servo 6 Maximum Value + * Magnetometer 1 X-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX6, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG1_XOFF, 0.0); /** - * SIM_GZ Servo 7 Maximum Value + * Magnetometer 2 X-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX7, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG2_XOFF, 0.0); /** - * SIM_GZ Servo 8 Maximum Value + * Magnetometer 3 X-axis offset * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX8, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG3_XOFF, 0.0); /** - * SIM_GZ Servo 1 Failsafe Value + * Magnetometer 0 Y-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC1). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL1, -1); +PARAM_DEFINE_FLOAT(CAL_MAG0_YOFF, 0.0); /** - * SIM_GZ Servo 2 Failsafe Value + * Magnetometer 1 Y-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC2). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL2, -1); +PARAM_DEFINE_FLOAT(CAL_MAG1_YOFF, 0.0); /** - * SIM_GZ Servo 3 Failsafe Value + * Magnetometer 2 Y-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC3). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL3, -1); +PARAM_DEFINE_FLOAT(CAL_MAG2_YOFF, 0.0); /** - * SIM_GZ Servo 4 Failsafe Value + * Magnetometer 3 Y-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC4). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL4, -1); +PARAM_DEFINE_FLOAT(CAL_MAG3_YOFF, 0.0); /** - * SIM_GZ Servo 5 Failsafe Value + * Magnetometer 0 Z-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC5). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL5, -1); +PARAM_DEFINE_FLOAT(CAL_MAG0_ZOFF, 0.0); /** - * SIM_GZ Servo 6 Failsafe Value + * Magnetometer 1 Z-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC6). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL6, -1); +PARAM_DEFINE_FLOAT(CAL_MAG1_ZOFF, 0.0); /** - * SIM_GZ Servo 7 Failsafe Value + * Magnetometer 2 Z-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC7). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL7, -1); +PARAM_DEFINE_FLOAT(CAL_MAG2_ZOFF, 0.0); /** - * SIM_GZ Servo 8 Failsafe Value + * Magnetometer 3 Z-axis offset * - * This is the output value that is set when in failsafe mode. - * - * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC8). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @unit gauss */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL8, -1); +PARAM_DEFINE_FLOAT(CAL_MAG3_ZOFF, 0.0); /** - * Reverse Output Range for SIM_GZ + * Magnetometer 0 X-axis scaling factor * - * Allows to reverse the output range for each channel. - * Note: this is only useful for servos. * * - * @group Actuator Outputs - * @bit 0 SIM_GZ ESC 1 - * @bit 1 SIM_GZ ESC 2 - * @bit 2 SIM_GZ ESC 3 - * @bit 3 SIM_GZ ESC 4 - * @bit 4 SIM_GZ ESC 5 - * @bit 5 SIM_GZ ESC 6 - * @bit 6 SIM_GZ ESC 7 - * @bit 7 SIM_GZ ESC 8 - * @min 0 - * @max 255 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_REV, 0); +PARAM_DEFINE_FLOAT(CAL_MAG0_XSCALE, 1.0); /** - * Reverse Output Range for SIM_GZ + * Magnetometer 1 X-axis scaling factor * - * Allows to reverse the output range for each channel. - * Note: this is only useful for servos. * * - * @group Actuator Outputs - * @bit 0 SIM_GZ Servo 1 - * @bit 1 SIM_GZ Servo 2 - * @bit 2 SIM_GZ Servo 3 - * @bit 3 SIM_GZ Servo 4 - * @bit 4 SIM_GZ Servo 5 - * @bit 5 SIM_GZ Servo 6 - * @bit 6 SIM_GZ Servo 7 - * @bit 7 SIM_GZ Servo 8 - * @min 0 - * @max 255 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_REV, 0); +PARAM_DEFINE_FLOAT(CAL_MAG1_XSCALE, 1.0); /** - * Airframe selection + * Magnetometer 2 X-axis scaling factor * - * Defines which mixer implementation to use. - * Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. - * - * 'Custom' should only be used if noting else can be used. * * - * @group Geometry - * @value 0 Multirotor - * @value 1 Fixed-wing - * @value 2 Standard VTOL - * @value 3 Tiltrotor VTOL - * @value 4 Tailsitter VTOL - * @value 5 Rover (Ackermann) - * @value 6 Rover (Differential) - * @value 7 Motors (6DOF) - * @value 8 Multirotor with Tilt - * @value 9 Custom - * @value 10 Helicopter + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CA_AIRFRAME, 0); +PARAM_DEFINE_FLOAT(CAL_MAG2_XSCALE, 1.0); /** - * Control allocation method + * Magnetometer 3 X-axis scaling factor * - * Selects the algorithm and desaturation method. - * If set to Automtic, the selection is based on the airframe (CA_AIRFRAME). * * - * @group Geometry - * @value 0 Pseudo-inverse with output clipping - * @value 1 Pseudo-inverse with sequential desaturation technique - * @value 2 Automatic + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CA_METHOD, 2); +PARAM_DEFINE_FLOAT(CAL_MAG3_XSCALE, 1.0); /** - * Bidirectional/Reversible motors + * Magnetometer 0 Y-axis scaling factor * - * Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well. * * - * @group Geometry - * @bit 0 Motor 1 - * @bit 1 Motor 2 - * @bit 2 Motor 3 - * @bit 3 Motor 4 - * @bit 4 Motor 5 - * @bit 5 Motor 6 - * @bit 6 Motor 7 - * @bit 7 Motor 8 - * @bit 8 Motor 9 - * @bit 9 Motor 10 - * @bit 10 Motor 11 - * @bit 11 Motor 12 - * @min 0 - * @max 4095 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CA_R_REV, 0); +PARAM_DEFINE_FLOAT(CAL_MAG0_YSCALE, 1.0); /** - * Motor 0 slew rate limit + * Magnetometer 1 Y-axis scaling factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(CA_R0_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_YSCALE, 1.0); /** - * Motor 1 slew rate limit + * Magnetometer 2 Y-axis scaling factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(CA_R1_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG2_YSCALE, 1.0); /** - * Motor 2 slew rate limit + * Magnetometer 3 Y-axis scaling factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(CA_R2_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG3_YSCALE, 1.0); /** - * Motor 3 slew rate limit + * Magnetometer 0 Z-axis scaling factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(CA_R3_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG0_ZSCALE, 1.0); /** - * Motor 4 slew rate limit + * Magnetometer 1 Z-axis scaling factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(CA_R4_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_ZSCALE, 1.0); /** - * Motor 5 slew rate limit + * Magnetometer 2 Z-axis scaling factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(CA_R5_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG2_ZSCALE, 1.0); /** - * Motor 6 slew rate limit + * Magnetometer 3 Z-axis scaling factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_FLOAT(CA_R6_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG3_ZSCALE, 1.0); /** - * Motor 7 slew rate limit + * Magnetometer 0 X-axis off diagonal scale factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_R7_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG0_XODIAG, 0.0); /** - * Motor 8 slew rate limit + * Magnetometer 1 X-axis off diagonal scale factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_R8_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_XODIAG, 0.0); /** - * Motor 9 slew rate limit + * Magnetometer 2 X-axis off diagonal scale factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). * - * Zero means that slew rate limiting is disabled. + * + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + */ +PARAM_DEFINE_FLOAT(CAL_MAG2_XODIAG, 0.0); + +/** + * Magnetometer 3 X-axis off diagonal scale factor + * * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_R9_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG3_XODIAG, 0.0); /** - * Motor 10 slew rate limit + * Magnetometer 0 Y-axis off diagonal scale factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_R10_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG0_YODIAG, 0.0); /** - * Motor 11 slew rate limit + * Magnetometer 1 Y-axis off diagonal scale factor * - * Minimum time allowed for the motor input signal to pass through - * the full output range. A value x means that the motor signal - * can only go from 0 to 1 in minimum x seconds (in case of - * reversible motors, the range is -1 to 1). - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.01 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_R11_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_YODIAG, 0.0); /** - * Servo 0 slew rate limit + * Magnetometer 2 Y-axis off diagonal scale factor * - * Minimum time allowed for the servo input signal to pass through - * the full output range. A value x means that the servo signal - * can only go from -1 to 1 in minimum x seconds. - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_SV0_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG2_YODIAG, 0.0); /** - * Servo 1 slew rate limit + * Magnetometer 3 Y-axis off diagonal scale factor * - * Minimum time allowed for the servo input signal to pass through - * the full output range. A value x means that the servo signal - * can only go from -1 to 1 in minimum x seconds. - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_SV1_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG3_YODIAG, 0.0); /** - * Servo 2 slew rate limit + * Magnetometer 0 Z-axis off diagonal scale factor * - * Minimum time allowed for the servo input signal to pass through - * the full output range. A value x means that the servo signal - * can only go from -1 to 1 in minimum x seconds. - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_SV2_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG0_ZODIAG, 0.0); /** - * Servo 3 slew rate limit + * Magnetometer 1 Z-axis off diagonal scale factor * - * Minimum time allowed for the servo input signal to pass through - * the full output range. A value x means that the servo signal - * can only go from -1 to 1 in minimum x seconds. - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_SV3_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_ZODIAG, 0.0); /** - * Servo 4 slew rate limit + * Magnetometer 2 Z-axis off diagonal scale factor * - * Minimum time allowed for the servo input signal to pass through - * the full output range. A value x means that the servo signal - * can only go from -1 to 1 in minimum x seconds. - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_SV4_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG2_ZODIAG, 0.0); /** - * Servo 5 slew rate limit + * Magnetometer 3 Z-axis off diagonal scale factor * - * Minimum time allowed for the servo input signal to pass through - * the full output range. A value x means that the servo signal - * can only go from -1 to 1 in minimum x seconds. - * - * Zero means that slew rate limiting is disabled. * * - * @group Geometry - * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_SV5_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG3_ZODIAG, 0.0); /** - * Servo 6 slew rate limit + * Magnetometer 0 X Axis throttle compensation * - * Minimum time allowed for the servo input signal to pass through - * the full output range. A value x means that the servo signal - * can only go from -1 to 1 in minimum x seconds. - * - * Zero means that slew rate limiting is disabled. + * Coefficient describing linear relationship between + * X component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_SV6_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG0_XCOMP, 0.0); /** - * Servo 7 slew rate limit + * Magnetometer 1 X Axis throttle compensation * - * Minimum time allowed for the servo input signal to pass through - * the full output range. A value x means that the servo signal - * can only go from -1 to 1 in minimum x seconds. - * - * Zero means that slew rate limiting is disabled. + * Coefficient describing linear relationship between + * X component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_SV7_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_XCOMP, 0.0); /** - * Total number of rotors + * Magnetometer 2 X Axis throttle compensation * + * Coefficient describing linear relationship between + * X component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @value 0 0 - * @value 1 1 - * @value 2 2 - * @value 3 3 - * @value 4 4 - * @value 5 5 - * @value 6 6 - * @value 7 7 - * @value 8 8 - * @value 9 9 - * @value 10 10 - * @value 11 11 - * @value 12 12 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(CA_ROTOR_COUNT, 0); +PARAM_DEFINE_FLOAT(CAL_MAG2_XCOMP, 0.0); /** - * Position of rotor 0 along X body axis + * Magnetometer 3 X Axis throttle compensation * + * Coefficient describing linear relationship between + * X component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG3_XCOMP, 0.0); /** - * Position of rotor 1 along X body axis + * Magnetometer 0 Y Axis throttle compensation * + * Coefficient describing linear relationship between + * Y component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG0_YCOMP, 0.0); /** - * Position of rotor 2 along X body axis + * Magnetometer 1 Y Axis throttle compensation * + * Coefficient describing linear relationship between + * Y component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_YCOMP, 0.0); /** - * Position of rotor 3 along X body axis + * Magnetometer 2 Y Axis throttle compensation * + * Coefficient describing linear relationship between + * Y component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG2_YCOMP, 0.0); /** - * Position of rotor 4 along X body axis + * Magnetometer 3 Y Axis throttle compensation * + * Coefficient describing linear relationship between + * Y component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG3_YCOMP, 0.0); /** - * Position of rotor 5 along X body axis + * Magnetometer 0 Z Axis throttle compensation * + * Coefficient describing linear relationship between + * Z component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG0_ZCOMP, 0.0); /** - * Position of rotor 6 along X body axis + * Magnetometer 1 Z Axis throttle compensation * + * Coefficient describing linear relationship between + * Z component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_ZCOMP, 0.0); /** - * Position of rotor 7 along X body axis + * Magnetometer 2 Z Axis throttle compensation * + * Coefficient describing linear relationship between + * Z component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG2_ZCOMP, 0.0); /** - * Position of rotor 8 along X body axis + * Magnetometer 3 Z Axis throttle compensation * + * Coefficient describing linear relationship between + * Z component of magnetometer in body frame axis + * and either current or throttle depending on value of CAL_MAG_COMP_TYP. + * Unit for throttle-based compensation is [G] and + * for current-based compensation [G/kA] * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_PX, 0.0); +PARAM_DEFINE_FLOAT(CAL_MAG3_ZCOMP, 0.0); /** - * Position of rotor 9 along X body axis + * SIM Channel 1 Output Function * + * Select what should be output on SIM Channel 1. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_PX, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC1, 0); /** - * Position of rotor 10 along X body axis + * SIM Channel 2 Output Function * + * Select what should be output on SIM Channel 2. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_PX, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC2, 0); /** - * Position of rotor 11 along X body axis + * SIM Channel 3 Output Function * + * Select what should be output on SIM Channel 3. * - * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m - */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_PX, 0.0); - -/** - * Position of rotor 0 along Y body axis - * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC3, 0); /** - * Position of rotor 1 along Y body axis + * SIM Channel 4 Output Function * + * Select what should be output on SIM Channel 4. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC4, 0); /** - * Position of rotor 2 along Y body axis + * SIM Channel 5 Output Function * + * Select what should be output on SIM Channel 5. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC5, 0); /** - * Position of rotor 3 along Y body axis + * SIM Channel 6 Output Function * + * Select what should be output on SIM Channel 6. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC6, 0); /** - * Position of rotor 4 along Y body axis + * SIM Channel 7 Output Function * + * Select what should be output on SIM Channel 7. * - * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m - */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_PY, 0.0); - -/** - * Position of rotor 5 along Y body axis - * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC7, 0); /** - * Position of rotor 6 along Y body axis + * SIM Channel 8 Output Function * + * Select what should be output on SIM Channel 8. * - * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m - */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_PY, 0.0); - -/** - * Position of rotor 7 along Y body axis - * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC8, 0); /** - * Position of rotor 8 along Y body axis + * SIM Channel 9 Output Function * + * Select what should be output on SIM Channel 9. * - * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m - */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_PY, 0.0); - -/** - * Position of rotor 9 along Y body axis - * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC9, 0); /** - * Position of rotor 10 along Y body axis + * SIM Channel 10 Output Function * + * Select what should be output on SIM Channel 10. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC10, 0); /** - * Position of rotor 11 along Y body axis + * SIM Channel 11 Output Function * + * Select what should be output on SIM Channel 11. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_PY, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC11, 0); /** - * Position of rotor 0 along Z body axis + * SIM Channel 12 Output Function * + * Select what should be output on SIM Channel 12. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_PZ, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC12, 0); /** - * Position of rotor 1 along Z body axis + * SIM Channel 13 Output Function * + * Select what should be output on SIM Channel 13. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_PZ, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC13, 0); /** - * Position of rotor 2 along Z body axis + * SIM Channel 14 Output Function * + * Select what should be output on SIM Channel 14. * - * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m - */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_PZ, 0.0); - -/** - * Position of rotor 3 along Z body axis - * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_PZ, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC14, 0); /** - * Position of rotor 4 along Z body axis + * SIM Channel 15 Output Function * + * Select what should be output on SIM Channel 15. * - * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m - */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_PZ, 0.0); - -/** - * Position of rotor 5 along Z body axis - * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_PZ, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC15, 0); /** - * Position of rotor 6 along Z body axis + * SIM Channel 16 Output Function * + * Select what should be output on SIM Channel 16. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_PZ, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_FUNC16, 0); /** - * Position of rotor 7 along Z body axis + * Reverse Output Range for SIM * + * Allows to reverse the output range for each channel. + * Note: this is only useful for servos. * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @bit 0 SIM Channel 1 + * @bit 1 SIM Channel 2 + * @bit 2 SIM Channel 3 + * @bit 3 SIM Channel 4 + * @bit 4 SIM Channel 5 + * @bit 5 SIM Channel 6 + * @bit 6 SIM Channel 7 + * @bit 7 SIM Channel 8 + * @bit 8 SIM Channel 9 + * @bit 9 SIM Channel 10 + * @bit 10 SIM Channel 11 + * @bit 11 SIM Channel 12 + * @bit 12 SIM Channel 13 + * @bit 13 SIM Channel 14 + * @bit 14 SIM Channel 15 + * @bit 15 SIM Channel 16 + * @min 0 + * @max 65535 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_PZ, 0.0); +PARAM_DEFINE_INT32(PWM_MAIN_REV, 0); /** - * Position of rotor 8 along Z body axis + * Enable Gripper actuation in Payload Deliverer * * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Payload Deliverer + * @boolean + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_PZ, 0.0); +PARAM_DEFINE_INT32(PD_GRIPPER_EN, 0); /** - * Position of rotor 9 along Z body axis + * Type of Gripper (Servo, etc.) * * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Payload Deliverer + * @value -1 Undefined + * @value 0 Servo + * @min -1 + * @max 0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_PZ, 0.0); +PARAM_DEFINE_INT32(PD_GRIPPER_TYPE, 0); /** - * Position of rotor 10 along Z body axis + * Timeout for successful gripper actuation acknowledgement * + * Maximum time Gripper will wait while the successful griper actuation isn't recognised. + * If the gripper has no feedback sensor, it will simply wait for + * this time before considering gripper actuation successful and publish a + * 'VehicleCommandAck' signaling successful gripper action * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Payload Deliverer + * @min 0 + * @unit s */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_PZ, 0.0); +PARAM_DEFINE_FLOAT(PD_GRIPPER_TO, 3); /** - * Position of rotor 11 along Z body axis + * UAVCAN ESC 1 Output Function * + * Select what should be output on UAVCAN ESC 1. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_PZ, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC1, 0); /** - * Axis of rotor 0 thrust vector, X body axis component + * UAVCAN ESC 2 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN ESC 2. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC2, 0); /** - * Axis of rotor 1 thrust vector, X body axis component + * UAVCAN ESC 3 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN ESC 3. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC3, 0); /** - * Axis of rotor 2 thrust vector, X body axis component + * UAVCAN ESC 4 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN ESC 4. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC4, 0); /** - * Axis of rotor 3 thrust vector, X body axis component + * UAVCAN ESC 5 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN ESC 5. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC5, 0); /** - * Axis of rotor 4 thrust vector, X body axis component + * UAVCAN ESC 6 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN ESC 6. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC6, 0); /** - * Axis of rotor 5 thrust vector, X body axis component + * UAVCAN ESC 7 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN ESC 7. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC7, 0); /** - * Axis of rotor 6 thrust vector, X body axis component + * UAVCAN ESC 8 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN ESC 8. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC8, 0); /** - * Axis of rotor 7 thrust vector, X body axis component + * UAVCAN ESC 1 Minimum Value * - * Only the direction is considered (the vector is normalized). + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN1, 1); /** - * Axis of rotor 8 thrust vector, X body axis component + * UAVCAN ESC 2 Minimum Value * - * Only the direction is considered (the vector is normalized). + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN2, 1); /** - * Axis of rotor 9 thrust vector, X body axis component + * UAVCAN ESC 3 Minimum Value * - * Only the direction is considered (the vector is normalized). + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN3, 1); /** - * Axis of rotor 10 thrust vector, X body axis component + * UAVCAN ESC 4 Minimum Value * - * Only the direction is considered (the vector is normalized). + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN4, 1); /** - * Axis of rotor 11 thrust vector, X body axis component + * UAVCAN ESC 5 Minimum Value * - * Only the direction is considered (the vector is normalized). + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_AX, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN5, 1); /** - * Axis of rotor 0 thrust vector, Y body axis component + * UAVCAN ESC 6 Minimum Value * - * Only the direction is considered (the vector is normalized). + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN6, 1); /** - * Axis of rotor 1 thrust vector, Y body axis component + * UAVCAN ESC 7 Minimum Value * - * Only the direction is considered (the vector is normalized). + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN7, 1); /** - * Axis of rotor 2 thrust vector, Y body axis component + * UAVCAN ESC 8 Minimum Value * - * Only the direction is considered (the vector is normalized). + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN8, 1); /** - * Axis of rotor 3 thrust vector, Y body axis component + * UAVCAN ESC 1 Maximum Value * - * Only the direction is considered (the vector is normalized). + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX1, 8191); /** - * Axis of rotor 4 thrust vector, Y body axis component + * UAVCAN ESC 2 Maximum Value * - * Only the direction is considered (the vector is normalized). + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX2, 8191); /** - * Axis of rotor 5 thrust vector, Y body axis component + * UAVCAN ESC 3 Maximum Value * - * Only the direction is considered (the vector is normalized). + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX3, 8191); /** - * Axis of rotor 6 thrust vector, Y body axis component + * UAVCAN ESC 4 Maximum Value * - * Only the direction is considered (the vector is normalized). + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX4, 8191); /** - * Axis of rotor 7 thrust vector, Y body axis component + * UAVCAN ESC 5 Maximum Value * - * Only the direction is considered (the vector is normalized). + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX5, 8191); /** - * Axis of rotor 8 thrust vector, Y body axis component + * UAVCAN ESC 6 Maximum Value * - * Only the direction is considered (the vector is normalized). + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX6, 8191); /** - * Axis of rotor 9 thrust vector, Y body axis component + * UAVCAN ESC 7 Maximum Value * - * Only the direction is considered (the vector is normalized). + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX7, 8191); /** - * Axis of rotor 10 thrust vector, Y body axis component + * UAVCAN ESC 8 Maximum Value * - * Only the direction is considered (the vector is normalized). + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX8, 8191); /** - * Axis of rotor 11 thrust vector, Y body axis component + * UAVCAN ESC 1 Failsafe Value * - * Only the direction is considered (the vector is normalized). + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC1). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_AY, 0.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL1, -1); /** - * Axis of rotor 0 thrust vector, Z body axis component + * UAVCAN ESC 2 Failsafe Value * - * Only the direction is considered (the vector is normalized). + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC2). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL2, -1); /** - * Axis of rotor 1 thrust vector, Z body axis component + * UAVCAN ESC 3 Failsafe Value * - * Only the direction is considered (the vector is normalized). + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC3). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL3, -1); /** - * Axis of rotor 2 thrust vector, Z body axis component + * UAVCAN ESC 4 Failsafe Value * - * Only the direction is considered (the vector is normalized). + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC4). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL4, -1); /** - * Axis of rotor 3 thrust vector, Z body axis component + * UAVCAN ESC 5 Failsafe Value * - * Only the direction is considered (the vector is normalized). + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC5). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL5, -1); /** - * Axis of rotor 4 thrust vector, Z body axis component + * UAVCAN ESC 6 Failsafe Value * - * Only the direction is considered (the vector is normalized). + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC6). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL6, -1); /** - * Axis of rotor 5 thrust vector, Z body axis component + * UAVCAN ESC 7 Failsafe Value * - * Only the direction is considered (the vector is normalized). + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC7). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL7, -1); /** - * Axis of rotor 6 thrust vector, Z body axis component + * UAVCAN ESC 8 Failsafe Value * - * Only the direction is considered (the vector is normalized). + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC8). + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL8, -1); /** - * Axis of rotor 7 thrust vector, Z body axis component + * UAVCAN Servo 1 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN Servo 1. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC1, 0); /** - * Axis of rotor 8 thrust vector, Z body axis component + * UAVCAN Servo 2 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN Servo 2. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC2, 0); /** - * Axis of rotor 9 thrust vector, Z body axis component + * UAVCAN Servo 3 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN Servo 3. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC3, 0); /** - * Axis of rotor 10 thrust vector, Z body axis component + * UAVCAN Servo 4 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN Servo 4. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC4, 0); /** - * Axis of rotor 11 thrust vector, Z body axis component + * UAVCAN Servo 5 Output Function * - * Only the direction is considered (the vector is normalized). + * Select what should be output on UAVCAN Servo 5. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_AZ, -1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC5, 0); /** - * Thrust coefficient of rotor 0 + * UAVCAN Servo 6 Output Function * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * Select what should be output on UAVCAN Servo 6. * - * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 - */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_CT, 6.5); - -/** - * Thrust coefficient of rotor 1 - * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC6, 0); /** - * Thrust coefficient of rotor 2 + * UAVCAN Servo 7 Output Function * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * Select what should be output on UAVCAN Servo 7. * - * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 - */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_CT, 6.5); - -/** - * Thrust coefficient of rotor 3 - * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC7, 0); /** - * Thrust coefficient of rotor 4 + * UAVCAN Servo 8 Output Function * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * Select what should be output on UAVCAN Servo 8. * - * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 - */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_CT, 6.5); - -/** - * Thrust coefficient of rotor 5 - * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest * * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC8, 0); /** - * Thrust coefficient of rotor 6 + * UAVCAN Servo 1 Disarmed Value * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 1 - * @increment 1 + * @group Actuator Outputs * @min 0 - * @max 100 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS1, 500); /** - * Thrust coefficient of rotor 7 + * UAVCAN Servo 2 Disarmed Value * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 1 - * @increment 1 + * @group Actuator Outputs * @min 0 - * @max 100 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS2, 500); /** - * Thrust coefficient of rotor 8 + * UAVCAN Servo 3 Disarmed Value * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 1 - * @increment 1 + * @group Actuator Outputs * @min 0 - * @max 100 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS3, 500); /** - * Thrust coefficient of rotor 9 + * UAVCAN Servo 4 Disarmed Value * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 1 - * @increment 1 + * @group Actuator Outputs * @min 0 - * @max 100 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS4, 500); /** - * Thrust coefficient of rotor 10 + * UAVCAN Servo 5 Disarmed Value * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 1 - * @increment 1 + * @group Actuator Outputs * @min 0 - * @max 100 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS5, 500); /** - * Thrust coefficient of rotor 11 + * UAVCAN Servo 6 Disarmed Value * - * The thrust coefficient if defined as Thrust = CT * u^2, - * where u (with value between actuator minimum and maximum) - * is the output signal sent to the motor controller. + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 1 - * @increment 1 + * @group Actuator Outputs * @min 0 - * @max 100 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_CT, 6.5); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS6, 500); /** - * Moment coefficient of rotor 0 + * UAVCAN Servo 7 Disarmed Value * - * The moment coefficient if defined as Torque = KM * Thrust. + * This is the output value that is set when not armed. * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS7, 500); /** - * Moment coefficient of rotor 1 + * UAVCAN Servo 8 Disarmed Value * - * The moment coefficient if defined as Torque = KM * Thrust. + * This is the output value that is set when not armed. * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS8, 500); /** - * Moment coefficient of rotor 2 + * UAVCAN Servo 1 Minimum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN1, 0); /** - * Moment coefficient of rotor 3 + * UAVCAN Servo 2 Minimum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN2, 0); /** - * Moment coefficient of rotor 4 + * UAVCAN Servo 3 Minimum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN3, 0); /** - * Moment coefficient of rotor 5 + * UAVCAN Servo 4 Minimum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN4, 0); /** - * Moment coefficient of rotor 6 + * UAVCAN Servo 5 Minimum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN5, 0); /** - * Moment coefficient of rotor 7 + * UAVCAN Servo 6 Minimum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN6, 0); /** - * Moment coefficient of rotor 8 - * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. - * + * UAVCAN Servo 7 Minimum Value * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * Minimum output value (when not disarmed). + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN7, 0); /** - * Moment coefficient of rotor 9 + * UAVCAN Servo 8 Minimum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN8, 0); /** - * Moment coefficient of rotor 10 + * UAVCAN Servo 1 Maximum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX1, 1000); /** - * Moment coefficient of rotor 11 + * UAVCAN Servo 2 Maximum Value * - * The moment coefficient if defined as Torque = KM * Thrust. - * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_KM, 0.05); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX2, 1000); /** - * Rotor 0 tilt assignment + * UAVCAN Servo 3 Maximum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR0_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX3, 1000); /** - * Rotor 1 tilt assignment + * UAVCAN Servo 4 Maximum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR1_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX4, 1000); /** - * Rotor 2 tilt assignment + * UAVCAN Servo 5 Maximum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR2_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX5, 1000); /** - * Rotor 3 tilt assignment + * UAVCAN Servo 6 Maximum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR3_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX6, 1000); /** - * Rotor 4 tilt assignment + * UAVCAN Servo 7 Maximum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR4_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX7, 1000); /** - * Rotor 5 tilt assignment + * UAVCAN Servo 8 Maximum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Maxmimum output value (when not disarmed). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR5_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX8, 1000); /** - * Rotor 6 tilt assignment + * UAVCAN Servo 1 Failsafe Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC1). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR6_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL1, -1); /** - * Rotor 7 tilt assignment + * UAVCAN Servo 2 Failsafe Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC2). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR7_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL2, -1); /** - * Rotor 8 tilt assignment + * UAVCAN Servo 3 Failsafe Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC3). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR8_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL3, -1); /** - * Rotor 9 tilt assignment + * UAVCAN Servo 4 Failsafe Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC4). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR9_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL4, -1); /** - * Rotor 10 tilt assignment + * UAVCAN Servo 5 Failsafe Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC5). + * * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR10_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL5, -1); /** - * Rotor 11 tilt assignment - * - * If not set to None, this motor is tilted by the configured tilt servo. + * UAVCAN Servo 6 Failsafe Value * - * @group Geometry - * @value 0 None - * @value 1 Tilt 1 - * @value 2 Tilt 2 - * @value 3 Tilt 3 - * @value 4 Tilt 4 + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC6). + * + * + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_ROTOR11_TILT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL6, -1); /** - * Total number of Control Surfaces + * UAVCAN Servo 7 Failsafe Value * + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC7). * * - * @group Geometry - * @value 0 0 - * @value 1 1 - * @value 2 2 - * @value 3 3 - * @value 4 4 - * @value 5 5 - * @value 6 6 - * @value 7 7 - * @value 8 8 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_CS_COUNT, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL7, -1); /** - * Control Surface 0 type + * UAVCAN Servo 8 Failsafe Value * + * This is the output value that is set when in failsafe mode. + * + * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC8). * * - * @group Geometry - * @value 0 (Not set) - * @value 1 Left Aileron - * @value 2 Right Aileron - * @value 3 Elevator - * @value 4 Rudder - * @value 5 Left Elevon - * @value 6 Right Elevon - * @value 7 Left V-Tail - * @value 8 Right V-Tail - * @value 9 Left Flap - * @value 10 Right Flap - * @value 11 Airbrake - * @value 12 Custom - * @value 13 Left A-tail - * @value 14 Right A-tail - * @value 15 Single Channel Aileron - * @value 16 Steering Wheel - * @value 17 Left Spoiler - * @value 18 Right Spoiler + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_CS0_TYPE, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL8, -1); /** - * Control Surface 1 type + * Reverse Output Range for UAVCAN * + * Allows to reverse the output range for each channel. + * Note: this is only useful for servos. * * - * @group Geometry - * @value 0 (Not set) - * @value 1 Left Aileron - * @value 2 Right Aileron - * @value 3 Elevator - * @value 4 Rudder - * @value 5 Left Elevon - * @value 6 Right Elevon - * @value 7 Left V-Tail - * @value 8 Right V-Tail - * @value 9 Left Flap - * @value 10 Right Flap - * @value 11 Airbrake - * @value 12 Custom - * @value 13 Left A-tail - * @value 14 Right A-tail - * @value 15 Single Channel Aileron - * @value 16 Steering Wheel - * @value 17 Left Spoiler - * @value 18 Right Spoiler + * @group Actuator Outputs + * @bit 0 UAVCAN ESC 1 + * @bit 1 UAVCAN ESC 2 + * @bit 2 UAVCAN ESC 3 + * @bit 3 UAVCAN ESC 4 + * @bit 4 UAVCAN ESC 5 + * @bit 5 UAVCAN ESC 6 + * @bit 6 UAVCAN ESC 7 + * @bit 7 UAVCAN ESC 8 + * @min 0 + * @max 255 */ -PARAM_DEFINE_INT32(CA_SV_CS1_TYPE, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_REV, 0); /** - * Control Surface 2 type + * Reverse Output Range for UAVCAN * + * Allows to reverse the output range for each channel. + * Note: this is only useful for servos. * * - * @group Geometry - * @value 0 (Not set) - * @value 1 Left Aileron - * @value 2 Right Aileron - * @value 3 Elevator - * @value 4 Rudder - * @value 5 Left Elevon - * @value 6 Right Elevon - * @value 7 Left V-Tail - * @value 8 Right V-Tail - * @value 9 Left Flap - * @value 10 Right Flap - * @value 11 Airbrake - * @value 12 Custom - * @value 13 Left A-tail - * @value 14 Right A-tail - * @value 15 Single Channel Aileron - * @value 16 Steering Wheel - * @value 17 Left Spoiler - * @value 18 Right Spoiler + * @group Actuator Outputs + * @bit 0 UAVCAN Servo 1 + * @bit 1 UAVCAN Servo 2 + * @bit 2 UAVCAN Servo 3 + * @bit 3 UAVCAN Servo 4 + * @bit 4 UAVCAN Servo 5 + * @bit 5 UAVCAN Servo 6 + * @bit 6 UAVCAN Servo 7 + * @bit 7 UAVCAN Servo 8 + * @min 0 + * @max 255 */ -PARAM_DEFINE_INT32(CA_SV_CS2_TYPE, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_REV, 0); /** - * Control Surface 3 type + * Battery 1 voltage divider (V divider) * + * This is the divider from battery 1 voltage to ADC voltage. + * If using e.g. Mauch power modules the value from the datasheet + * can be applied straight here. A value of -1 means to use + * the board default. * * - * @group Geometry - * @value 0 (Not set) - * @value 1 Left Aileron - * @value 2 Right Aileron - * @value 3 Elevator - * @value 4 Rudder - * @value 5 Left Elevon - * @value 6 Right Elevon - * @value 7 Left V-Tail - * @value 8 Right V-Tail - * @value 9 Left Flap - * @value 10 Right Flap - * @value 11 Airbrake - * @value 12 Custom - * @value 13 Left A-tail - * @value 14 Right A-tail - * @value 15 Single Channel Aileron - * @value 16 Steering Wheel - * @value 17 Left Spoiler - * @value 18 Right Spoiler + * @group Battery Calibration + * @decimal 8 + * @reboot_required True */ -PARAM_DEFINE_INT32(CA_SV_CS3_TYPE, 0); +PARAM_DEFINE_FLOAT(BAT1_V_DIV, -1.0); /** - * Control Surface 4 type + * Battery 2 voltage divider (V divider) * + * This is the divider from battery 2 voltage to ADC voltage. + * If using e.g. Mauch power modules the value from the datasheet + * can be applied straight here. A value of -1 means to use + * the board default. * * - * @group Geometry - * @value 0 (Not set) - * @value 1 Left Aileron - * @value 2 Right Aileron - * @value 3 Elevator - * @value 4 Rudder - * @value 5 Left Elevon - * @value 6 Right Elevon - * @value 7 Left V-Tail - * @value 8 Right V-Tail - * @value 9 Left Flap - * @value 10 Right Flap - * @value 11 Airbrake - * @value 12 Custom - * @value 13 Left A-tail - * @value 14 Right A-tail - * @value 15 Single Channel Aileron - * @value 16 Steering Wheel - * @value 17 Left Spoiler - * @value 18 Right Spoiler + * @group Battery Calibration + * @decimal 8 + * @reboot_required True */ -PARAM_DEFINE_INT32(CA_SV_CS4_TYPE, 0); +PARAM_DEFINE_FLOAT(BAT2_V_DIV, -1.0); /** - * Control Surface 5 type + * Battery 1 current per volt (A/V) * + * The voltage seen by the ADC multiplied by this factor + * will determine the battery current. A value of -1 means to use + * the board default. * * - * @group Geometry - * @value 0 (Not set) - * @value 1 Left Aileron - * @value 2 Right Aileron - * @value 3 Elevator - * @value 4 Rudder - * @value 5 Left Elevon - * @value 6 Right Elevon - * @value 7 Left V-Tail - * @value 8 Right V-Tail - * @value 9 Left Flap - * @value 10 Right Flap - * @value 11 Airbrake - * @value 12 Custom - * @value 13 Left A-tail - * @value 14 Right A-tail - * @value 15 Single Channel Aileron - * @value 16 Steering Wheel - * @value 17 Left Spoiler - * @value 18 Right Spoiler + * @group Battery Calibration + * @decimal 8 + * @reboot_required True */ -PARAM_DEFINE_INT32(CA_SV_CS5_TYPE, 0); +PARAM_DEFINE_FLOAT(BAT1_A_PER_V, -1.0); /** - * Control Surface 6 type + * Battery 2 current per volt (A/V) * + * The voltage seen by the ADC multiplied by this factor + * will determine the battery current. A value of -1 means to use + * the board default. * * - * @group Geometry - * @value 0 (Not set) - * @value 1 Left Aileron - * @value 2 Right Aileron - * @value 3 Elevator - * @value 4 Rudder - * @value 5 Left Elevon - * @value 6 Right Elevon - * @value 7 Left V-Tail - * @value 8 Right V-Tail - * @value 9 Left Flap - * @value 10 Right Flap - * @value 11 Airbrake - * @value 12 Custom - * @value 13 Left A-tail - * @value 14 Right A-tail - * @value 15 Single Channel Aileron - * @value 16 Steering Wheel - * @value 17 Left Spoiler - * @value 18 Right Spoiler + * @group Battery Calibration + * @decimal 8 + * @reboot_required True + */ +PARAM_DEFINE_FLOAT(BAT2_A_PER_V, -1.0); + +/** + * Battery 1 Voltage ADC Channel + * + * This parameter specifies the ADC channel used to monitor voltage of main power battery. + * A value of -1 means to use the board default. + * + * + * @group Battery Calibration + * @reboot_required True */ -PARAM_DEFINE_INT32(CA_SV_CS6_TYPE, 0); +PARAM_DEFINE_INT32(BAT1_V_CHANNEL, -1); /** - * Control Surface 7 type + * Battery 2 Voltage ADC Channel * + * This parameter specifies the ADC channel used to monitor voltage of main power battery. + * A value of -1 means to use the board default. * * - * @group Geometry - * @value 0 (Not set) - * @value 1 Left Aileron - * @value 2 Right Aileron - * @value 3 Elevator - * @value 4 Rudder - * @value 5 Left Elevon - * @value 6 Right Elevon - * @value 7 Left V-Tail - * @value 8 Right V-Tail - * @value 9 Left Flap - * @value 10 Right Flap - * @value 11 Airbrake - * @value 12 Custom - * @value 13 Left A-tail - * @value 14 Right A-tail - * @value 15 Single Channel Aileron - * @value 16 Steering Wheel - * @value 17 Left Spoiler - * @value 18 Right Spoiler + * @group Battery Calibration + * @reboot_required True */ -PARAM_DEFINE_INT32(CA_SV_CS7_TYPE, 0); +PARAM_DEFINE_INT32(BAT2_V_CHANNEL, -1); /** - * Control Surface 0 roll torque scaling + * Battery 1 Current ADC Channel * + * This parameter specifies the ADC channel used to monitor current of main power battery. + * A value of -1 means to use the board default. * * - * @group Geometry - * @decimal 2 + * @group Battery Calibration + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_R, 0.0); +PARAM_DEFINE_INT32(BAT1_I_CHANNEL, -1); /** - * Control Surface 1 roll torque scaling + * Battery 2 Current ADC Channel * + * This parameter specifies the ADC channel used to monitor current of main power battery. + * A value of -1 means to use the board default. * * - * @group Geometry - * @decimal 2 + * @group Battery Calibration + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_R, 0.0); +PARAM_DEFINE_INT32(BAT2_I_CHANNEL, -1); /** - * Control Surface 2 roll torque scaling + * Airframe selection * + * Defines which mixer implementation to use. + * Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. + * + * 'Custom' should only be used if noting else can be used. * * * @group Geometry - * @decimal 2 + * @value 0 Multirotor + * @value 1 Fixed-wing + * @value 2 Standard VTOL + * @value 3 Tiltrotor VTOL + * @value 4 Tailsitter VTOL + * @value 5 Rover (Ackermann) + * @value 6 Rover (Differential) + * @value 7 Motors (6DOF) + * @value 8 Multirotor with Tilt + * @value 9 Custom + * @value 10 Helicopter */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_R, 0.0); +PARAM_DEFINE_INT32(CA_AIRFRAME, 0); /** - * Control Surface 3 roll torque scaling + * Control allocation method * + * Selects the algorithm and desaturation method. + * If set to Automtic, the selection is based on the airframe (CA_AIRFRAME). * * * @group Geometry - * @decimal 2 + * @value 0 Pseudo-inverse with output clipping + * @value 1 Pseudo-inverse with sequential desaturation technique + * @value 2 Automatic */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_R, 0.0); +PARAM_DEFINE_INT32(CA_METHOD, 2); /** - * Control Surface 4 roll torque scaling + * Bidirectional/Reversible motors * + * Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well. * * * @group Geometry - * @decimal 2 + * @bit 0 Motor 1 + * @bit 1 Motor 2 + * @bit 2 Motor 3 + * @bit 3 Motor 4 + * @bit 4 Motor 5 + * @bit 5 Motor 6 + * @bit 6 Motor 7 + * @bit 7 Motor 8 + * @bit 8 Motor 9 + * @bit 9 Motor 10 + * @bit 10 Motor 11 + * @bit 11 Motor 12 + * @min 0 + * @max 4095 */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_R, 0.0); +PARAM_DEFINE_INT32(CA_R_REV, 0); /** - * Control Surface 5 roll torque scaling + * Motor 0 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_R, 0.0); +PARAM_DEFINE_FLOAT(CA_R0_SLEW, 0.0); /** - * Control Surface 6 roll torque scaling + * Motor 1 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_R, 0.0); +PARAM_DEFINE_FLOAT(CA_R1_SLEW, 0.0); /** - * Control Surface 7 roll torque scaling + * Motor 2 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_R, 0.0); +PARAM_DEFINE_FLOAT(CA_R2_SLEW, 0.0); /** - * Control Surface 0 pitch torque scaling + * Motor 3 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_P, 0.0); +PARAM_DEFINE_FLOAT(CA_R3_SLEW, 0.0); /** - * Control Surface 1 pitch torque scaling + * Motor 4 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_P, 0.0); +PARAM_DEFINE_FLOAT(CA_R4_SLEW, 0.0); /** - * Control Surface 2 pitch torque scaling + * Motor 5 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_P, 0.0); +PARAM_DEFINE_FLOAT(CA_R5_SLEW, 0.0); /** - * Control Surface 3 pitch torque scaling + * Motor 6 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_P, 0.0); +PARAM_DEFINE_FLOAT(CA_R6_SLEW, 0.0); /** - * Control Surface 4 pitch torque scaling + * Motor 7 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_P, 0.0); +PARAM_DEFINE_FLOAT(CA_R7_SLEW, 0.0); /** - * Control Surface 5 pitch torque scaling + * Motor 8 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_P, 0.0); +PARAM_DEFINE_FLOAT(CA_R8_SLEW, 0.0); /** - * Control Surface 6 pitch torque scaling + * Motor 9 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_P, 0.0); +PARAM_DEFINE_FLOAT(CA_R9_SLEW, 0.0); /** - * Control Surface 7 pitch torque scaling + * Motor 10 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_P, 0.0); +PARAM_DEFINE_FLOAT(CA_R10_SLEW, 0.0); /** - * Control Surface 0 yaw torque scaling + * Motor 11 slew rate limit * + * Minimum time allowed for the motor input signal to pass through + * the full output range. A value x means that the motor signal + * can only go from 0 to 1 in minimum x seconds (in case of + * reversible motors, the range is -1 to 1). + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_Y, 0.0); +PARAM_DEFINE_FLOAT(CA_R11_SLEW, 0.0); /** - * Control Surface 1 yaw torque scaling + * Servo 0 slew rate limit * + * Minimum time allowed for the servo input signal to pass through + * the full output range. A value x means that the servo signal + * can only go from -1 to 1 in minimum x seconds. + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.05 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_Y, 0.0); +PARAM_DEFINE_FLOAT(CA_SV0_SLEW, 0.0); /** - * Control Surface 2 yaw torque scaling + * Servo 1 slew rate limit * + * Minimum time allowed for the servo input signal to pass through + * the full output range. A value x means that the servo signal + * can only go from -1 to 1 in minimum x seconds. + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.05 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_Y, 0.0); +PARAM_DEFINE_FLOAT(CA_SV1_SLEW, 0.0); /** - * Control Surface 3 yaw torque scaling + * Servo 2 slew rate limit * + * Minimum time allowed for the servo input signal to pass through + * the full output range. A value x means that the servo signal + * can only go from -1 to 1 in minimum x seconds. + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.05 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_Y, 0.0); +PARAM_DEFINE_FLOAT(CA_SV2_SLEW, 0.0); /** - * Control Surface 4 yaw torque scaling + * Servo 3 slew rate limit * + * Minimum time allowed for the servo input signal to pass through + * the full output range. A value x means that the servo signal + * can only go from -1 to 1 in minimum x seconds. + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.05 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_Y, 0.0); +PARAM_DEFINE_FLOAT(CA_SV3_SLEW, 0.0); /** - * Control Surface 5 yaw torque scaling + * Servo 4 slew rate limit * + * Minimum time allowed for the servo input signal to pass through + * the full output range. A value x means that the servo signal + * can only go from -1 to 1 in minimum x seconds. + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.05 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_Y, 0.0); +PARAM_DEFINE_FLOAT(CA_SV4_SLEW, 0.0); /** - * Control Surface 6 yaw torque scaling + * Servo 5 slew rate limit * + * Minimum time allowed for the servo input signal to pass through + * the full output range. A value x means that the servo signal + * can only go from -1 to 1 in minimum x seconds. + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.05 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_Y, 0.0); +PARAM_DEFINE_FLOAT(CA_SV5_SLEW, 0.0); /** - * Control Surface 7 yaw torque scaling + * Servo 6 slew rate limit * + * Minimum time allowed for the servo input signal to pass through + * the full output range. A value x means that the servo signal + * can only go from -1 to 1 in minimum x seconds. + * + * Zero means that slew rate limiting is disabled. * * * @group Geometry * @decimal 2 + * @increment 0.05 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_Y, 0.0); +PARAM_DEFINE_FLOAT(CA_SV6_SLEW, 0.0); /** - * Control Surface 0 trim + * Servo 7 slew rate limit * - * Can be used to add an offset to the servo control. + * Minimum time allowed for the servo input signal to pass through + * the full output range. A value x means that the servo signal + * can only go from -1 to 1 in minimum x seconds. + * + * Zero means that slew rate limiting is disabled. + * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.05 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_TRIM, 0.0); +PARAM_DEFINE_FLOAT(CA_SV7_SLEW, 0.0); /** - * Control Surface 1 trim + * Total number of rotors * - * Can be used to add an offset to the servo control. + * * * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @value 0 0 + * @value 1 1 + * @value 2 2 + * @value 3 3 + * @value 4 4 + * @value 5 5 + * @value 6 6 + * @value 7 7 + * @value 8 8 + * @value 9 9 + * @value 10 10 + * @value 11 11 + * @value 12 12 */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_TRIM, 0.0); +PARAM_DEFINE_INT32(CA_ROTOR_COUNT, 0); /** - * Control Surface 2 trim + * Position of rotor 0 along X body axis * - * Can be used to add an offset to the servo control. + * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_TRIM, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR0_PX, 0.0); /** - * Control Surface 3 trim + * Position of rotor 1 along X body axis * - * Can be used to add an offset to the servo control. + * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_TRIM, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR1_PX, 0.0); /** - * Control Surface 4 trim + * Position of rotor 2 along X body axis * - * Can be used to add an offset to the servo control. + * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_TRIM, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR2_PX, 0.0); /** - * Control Surface 5 trim + * Position of rotor 3 along X body axis * - * Can be used to add an offset to the servo control. + * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_TRIM, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR3_PX, 0.0); /** - * Control Surface 6 trim + * Position of rotor 4 along X body axis * - * Can be used to add an offset to the servo control. + * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_TRIM, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR4_PX, 0.0); /** - * Control Surface 7 trim + * Position of rotor 5 along X body axis * - * Can be used to add an offset to the servo control. + * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_TRIM, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR5_PX, 0.0); /** - * Control Surface 0 configuration as flap + * Position of rotor 6 along X body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_FLAP, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR6_PX, 0.0); /** - * Control Surface 1 configuration as flap + * Position of rotor 7 along X body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_FLAP, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR7_PX, 0.0); /** - * Control Surface 2 configuration as flap + * Position of rotor 8 along X body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_FLAP, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR8_PX, 0.0); /** - * Control Surface 3 configuration as flap + * Position of rotor 9 along X body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_FLAP, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR9_PX, 0.0); /** - * Control Surface 4 configuration as flap + * Position of rotor 10 along X body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_FLAP, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR10_PX, 0.0); /** - * Control Surface 5 configuration as flap + * Position of rotor 11 along X body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_FLAP, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_PX, 0.0); /** - * Control Surface 6 configuration as flap + * Position of rotor 0 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_FLAP, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR0_PY, 0.0); /** - * Control Surface 7 configuration as flap + * Position of rotor 1 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_FLAP, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR1_PY, 0.0); /** - * Control Surface 0 configuration as spoiler + * Position of rotor 2 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_SPOIL, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR2_PY, 0.0); /** - * Control Surface 1 configuration as spoiler + * Position of rotor 3 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_SPOIL, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR3_PY, 0.0); /** - * Control Surface 2 configuration as spoiler + * Position of rotor 4 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_SPOIL, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR4_PY, 0.0); /** - * Control Surface 3 configuration as spoiler + * Position of rotor 5 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_SPOIL, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR5_PY, 0.0); /** - * Control Surface 4 configuration as spoiler + * Position of rotor 6 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_SPOIL, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR6_PY, 0.0); /** - * Control Surface 5 configuration as spoiler + * Position of rotor 7 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_SPOIL, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR7_PY, 0.0); /** - * Control Surface 6 configuration as spoiler + * Position of rotor 8 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_SPOIL, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR8_PY, 0.0); /** - * Control Surface 7 configuration as spoiler + * Position of rotor 9 along Y body axis * * * * @group Geometry * @decimal 2 - * @min -1.0 - * @max 1.0 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_SPOIL, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR9_PY, 0.0); /** - * Total number of Tilt Servos + * Position of rotor 10 along Y body axis * * * * @group Geometry - * @value 0 0 - * @value 1 1 - * @value 2 2 - * @value 3 3 - * @value 4 4 + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(CA_SV_TL_COUNT, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR10_PY, 0.0); /** - * Tilt 0 is used for control + * Position of rotor 11 along Y body axis * - * Define if this servo is used for additional control. + * * * @group Geometry - * @value 0 None - * @value 1 Yaw - * @value 2 Pitch - * @value 3 Yaw and Pitch + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(CA_SV_TL0_CT, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR11_PY, 0.0); /** - * Tilt 1 is used for control + * Position of rotor 0 along Z body axis * - * Define if this servo is used for additional control. + * * * @group Geometry - * @value 0 None - * @value 1 Yaw - * @value 2 Pitch - * @value 3 Yaw and Pitch + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(CA_SV_TL1_CT, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR0_PZ, 0.0); /** - * Tilt 2 is used for control + * Position of rotor 1 along Z body axis * - * Define if this servo is used for additional control. + * * * @group Geometry - * @value 0 None - * @value 1 Yaw - * @value 2 Pitch - * @value 3 Yaw and Pitch + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(CA_SV_TL2_CT, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR1_PZ, 0.0); /** - * Tilt 3 is used for control + * Position of rotor 2 along Z body axis * - * Define if this servo is used for additional control. + * * * @group Geometry - * @value 0 None - * @value 1 Yaw - * @value 2 Pitch - * @value 3 Yaw and Pitch + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(CA_SV_TL3_CT, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR2_PZ, 0.0); /** - * Tilt Servo 0 Tilt Angle at Minimum + * Position of rotor 3 along Z body axis * - * Defines the tilt angle when the servo is at the minimum. - * An angle of zero means upwards. * * * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_TL0_MINA, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR3_PZ, 0.0); /** - * Tilt Servo 1 Tilt Angle at Minimum + * Position of rotor 4 along Z body axis * - * Defines the tilt angle when the servo is at the minimum. - * An angle of zero means upwards. * * * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_TL1_MINA, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR4_PZ, 0.0); /** - * Tilt Servo 2 Tilt Angle at Minimum + * Position of rotor 5 along Z body axis * - * Defines the tilt angle when the servo is at the minimum. - * An angle of zero means upwards. * * * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_TL2_MINA, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR5_PZ, 0.0); /** - * Tilt Servo 3 Tilt Angle at Minimum + * Position of rotor 6 along Z body axis * - * Defines the tilt angle when the servo is at the minimum. - * An angle of zero means upwards. * * * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_TL3_MINA, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR6_PZ, 0.0); /** - * Tilt Servo 0 Tilt Angle at Maximum + * Position of rotor 7 along Z body axis * - * Defines the tilt angle when the servo is at the maximum. - * An angle of zero means upwards. * * * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_TL0_MAXA, 90.0); +PARAM_DEFINE_FLOAT(CA_ROTOR7_PZ, 0.0); /** - * Tilt Servo 1 Tilt Angle at Maximum + * Position of rotor 8 along Z body axis * - * Defines the tilt angle when the servo is at the maximum. - * An angle of zero means upwards. * * * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_TL1_MAXA, 90.0); +PARAM_DEFINE_FLOAT(CA_ROTOR8_PZ, 0.0); /** - * Tilt Servo 2 Tilt Angle at Maximum + * Position of rotor 9 along Z body axis * - * Defines the tilt angle when the servo is at the maximum. - * An angle of zero means upwards. * * * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_TL2_MAXA, 90.0); +PARAM_DEFINE_FLOAT(CA_ROTOR9_PZ, 0.0); /** - * Tilt Servo 3 Tilt Angle at Maximum + * Position of rotor 10 along Z body axis * - * Defines the tilt angle when the servo is at the maximum. - * An angle of zero means upwards. * * * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_FLOAT(CA_SV_TL3_MAXA, 90.0); +PARAM_DEFINE_FLOAT(CA_ROTOR10_PZ, 0.0); /** - * Tilt Servo 0 Tilt Direction + * Position of rotor 11 along Z body axis * - * Defines the direction the servo tilts towards when moving towards the maximum tilt angle. - * For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', - * the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. * * * @group Geometry - * @value 0 Towards Front - * @value 90 Towards Right - * @min 0 - * @max 359 + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(CA_SV_TL0_TD, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_PZ, 0.0); /** - * Tilt Servo 1 Tilt Direction + * Axis of rotor 0 thrust vector, X body axis component * - * Defines the direction the servo tilts towards when moving towards the maximum tilt angle. - * For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', - * the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @value 0 Towards Front - * @value 90 Towards Right - * @min 0 - * @max 359 + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CA_SV_TL1_TD, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR0_AX, 0.0); /** - * Tilt Servo 2 Tilt Direction + * Axis of rotor 1 thrust vector, X body axis component * - * Defines the direction the servo tilts towards when moving towards the maximum tilt angle. - * For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', - * the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @value 0 Towards Front - * @value 90 Towards Right - * @min 0 - * @max 359 + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CA_SV_TL2_TD, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR1_AX, 0.0); /** - * Tilt Servo 3 Tilt Direction + * Axis of rotor 2 thrust vector, X body axis component * - * Defines the direction the servo tilts towards when moving towards the maximum tilt angle. - * For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', - * the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @value 0 Towards Front - * @value 90 Towards Right - * @min 0 - * @max 359 + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CA_SV_TL3_TD, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR2_AX, 0.0); /** - * Number of swash plates servos + * Axis of rotor 3 thrust vector, X body axis component * - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @value 3 3 - * @value 4 4 + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CA_SP0_COUNT, 3); +PARAM_DEFINE_FLOAT(CA_ROTOR3_AX, 0.0); /** - * Angle for swash plate servo 0 + * Axis of rotor 4 thrust vector, X body axis component * - * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 0 - * @increment 10 - * @min 0 - * @max 360 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_SP0_ANG0, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR4_AX, 0.0); /** - * Angle for swash plate servo 1 + * Axis of rotor 5 thrust vector, X body axis component * - * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 0 - * @increment 10 - * @min 0 - * @max 360 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_SP0_ANG1, 140); +PARAM_DEFINE_FLOAT(CA_ROTOR5_AX, 0.0); /** - * Angle for swash plate servo 2 + * Axis of rotor 6 thrust vector, X body axis component * - * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 0 - * @increment 10 - * @min 0 - * @max 360 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_SP0_ANG2, 220); +PARAM_DEFINE_FLOAT(CA_ROTOR6_AX, 0.0); /** - * Angle for swash plate servo 3 + * Axis of rotor 7 thrust vector, X body axis component * - * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 0 - * @increment 10 - * @min 0 - * @max 360 - * @unit deg + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_SP0_ANG3, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR7_AX, 0.0); /** - * Arm length for swash plate servo 0 + * Axis of rotor 8 thrust vector, X body axis component * - * This is relative to the other arm lengths. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 10 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_SP0_ARM_L0, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR8_AX, 0.0); /** - * Arm length for swash plate servo 1 + * Axis of rotor 9 thrust vector, X body axis component * - * This is relative to the other arm lengths. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 10 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_SP0_ARM_L1, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR9_AX, 0.0); /** - * Arm length for swash plate servo 2 + * Axis of rotor 10 thrust vector, X body axis component * - * This is relative to the other arm lengths. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 10 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_SP0_ARM_L2, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR10_AX, 0.0); /** - * Arm length for swash plate servo 3 + * Axis of rotor 11 thrust vector, X body axis component * - * This is relative to the other arm lengths. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 10 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_SP0_ARM_L3, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_AX, 0.0); /** - * Throttle curve at position 0 + * Axis of rotor 0 thrust vector, Y body axis component * - * Defines the output throttle at the interval position 0. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C0, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR0_AY, 0.0); /** - * Throttle curve at position 1 + * Axis of rotor 1 thrust vector, Y body axis component * - * Defines the output throttle at the interval position 1. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C1, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR1_AY, 0.0); /** - * Throttle curve at position 2 + * Axis of rotor 2 thrust vector, Y body axis component * - * Defines the output throttle at the interval position 2. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C2, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR2_AY, 0.0); /** - * Throttle curve at position 3 + * Axis of rotor 3 thrust vector, Y body axis component * - * Defines the output throttle at the interval position 3. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C3, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR3_AY, 0.0); /** - * Throttle curve at position 4 + * Axis of rotor 4 thrust vector, Y body axis component * - * Defines the output throttle at the interval position 4. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min 0 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C4, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR4_AY, 0.0); /** - * Collective pitch curve at position 0 + * Axis of rotor 5 thrust vector, Y body axis component * - * Defines the collective pitch at the interval position 0 for a given thrust setpoint. - * - * Use negative values if the swash plate needs to move down to provide upwards thrust. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min -1 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C0, -0.05); +PARAM_DEFINE_FLOAT(CA_ROTOR5_AY, 0.0); /** - * Collective pitch curve at position 1 + * Axis of rotor 6 thrust vector, Y body axis component * - * Defines the collective pitch at the interval position 1 for a given thrust setpoint. - * - * Use negative values if the swash plate needs to move down to provide upwards thrust. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min -1 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C1, 0.0725); +PARAM_DEFINE_FLOAT(CA_ROTOR6_AY, 0.0); /** - * Collective pitch curve at position 2 + * Axis of rotor 7 thrust vector, Y body axis component * - * Defines the collective pitch at the interval position 2 for a given thrust setpoint. - * - * Use negative values if the swash plate needs to move down to provide upwards thrust. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min -1 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C2, 0.2); +PARAM_DEFINE_FLOAT(CA_ROTOR7_AY, 0.0); /** - * Collective pitch curve at position 3 + * Axis of rotor 8 thrust vector, Y body axis component * - * Defines the collective pitch at the interval position 3 for a given thrust setpoint. - * - * Use negative values if the swash plate needs to move down to provide upwards thrust. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min -1 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C3, 0.325); +PARAM_DEFINE_FLOAT(CA_ROTOR8_AY, 0.0); /** - * Collective pitch curve at position 4 + * Axis of rotor 9 thrust vector, Y body axis component * - * Defines the collective pitch at the interval position 4 for a given thrust setpoint. - * - * Use negative values if the swash plate needs to move down to provide upwards thrust. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min -1 - * @max 1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C4, 0.45); +PARAM_DEFINE_FLOAT(CA_ROTOR9_AY, 0.0); /** - * Scale for yaw compensation based on collective pitch + * Axis of rotor 10 thrust vector, Y body axis component * - * This allows to add a proportional factor of the collective pitch command to the yaw command. - * A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. - * - * tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O) - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min -2 - * @max 2 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_YAW_CP_S, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR10_AY, 0.0); /** - * Offset for yaw compensation based on collective pitch + * Axis of rotor 11 thrust vector, Y body axis component * - * This allows to specify which collective pitch command results in the least amount of rotor drag. - * This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch - * by aligning the lowest rotor drag with zero compensation. - * For symmetric profile blades this is the command that results in exactly 0° collective blade angle. - * For lift profile blades this is typically a command resulting in slightly negative collective blade angle. - * - * tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O) - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min -2 - * @max 2 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_YAW_CP_O, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_AY, 0.0); /** - * Scale for yaw compensation based on throttle + * Axis of rotor 0 thrust vector, Z body axis component * - * This allows to add a proportional factor of the throttle command to the yaw command. - * A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. - * - * tail_output += CA_HELI_YAW_TH_S * throttle - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @decimal 3 + * @decimal 2 * @increment 0.1 - * @min -2 - * @max 2 + * @min -100 + * @max 100 */ -PARAM_DEFINE_FLOAT(CA_HELI_YAW_TH_S, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR0_AZ, -1.0); /** - * Main rotor turns counter-clockwise + * Axis of rotor 1 thrust vector, Z body axis component * - * Default configuration is for a clockwise turning main rotor and - * positive thrust of the tail rotor is expected to rotate the vehicle clockwise. - * Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction - * which is mostly the case when the main rotor turns counter-clockwise. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @boolean + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CA_HELI_YAW_CCW, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR1_AZ, -1.0); /** - * Motor failure handling mode + * Axis of rotor 2 thrust vector, Z body axis component * - * This is used to specify how to handle motor failures - * reported by failure detector. - * + * Only the direction is considered (the vector is normalized). * * @group Geometry - * @value 0 Ignore - * @value 1 Remove first failed motor from effectiveness + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CA_FAILURE_MODE, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR2_AZ, -1.0); /** - * Accelerometer 0 calibration device ID + * Axis of rotor 3 thrust vector, Z body axis component * - * Device ID of the accelerometer this calibration applies to. + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @decimal 3 - * @category System + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC0_ID, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR3_AZ, -1.0); /** - * Accelerometer 1 calibration device ID + * Axis of rotor 4 thrust vector, Z body axis component * - * Device ID of the accelerometer this calibration applies to. + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @decimal 3 - * @category System + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC1_ID, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR4_AZ, -1.0); /** - * Accelerometer 2 calibration device ID + * Axis of rotor 5 thrust vector, Z body axis component * - * Device ID of the accelerometer this calibration applies to. + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @decimal 3 - * @category System + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC2_ID, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR5_AZ, -1.0); /** - * Accelerometer 3 calibration device ID + * Axis of rotor 6 thrust vector, Z body axis component * - * Device ID of the accelerometer this calibration applies to. + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @decimal 3 - * @category System + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC3_ID, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR6_AZ, -1.0); /** - * Accelerometer 0 priority + * Axis of rotor 7 thrust vector, Z body axis component * - * + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @decimal 3 - * @category System + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC0_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR7_AZ, -1.0); /** - * Accelerometer 1 priority + * Axis of rotor 8 thrust vector, Z body axis component * - * + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @decimal 3 - * @category System + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC1_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR8_AZ, -1.0); /** - * Accelerometer 2 priority + * Axis of rotor 9 thrust vector, Z body axis component * - * + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @decimal 3 - * @category System + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC2_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR9_AZ, -1.0); /** - * Accelerometer 3 priority + * Axis of rotor 10 thrust vector, Z body axis component * - * + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @decimal 3 - * @category System + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC3_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR10_AZ, -1.0); /** - * Accelerometer 0 rotation relative to airframe + * Axis of rotor 11 thrust vector, Z body axis component * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - * + * Only the direction is considered (the vector is normalized). * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC0_ROT, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR11_AZ, -1.0); /** - * Accelerometer 1 rotation relative to airframe + * Thrust coefficient of rotor 0 * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC1_ROT, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR0_CT, 6.5); /** - * Accelerometer 2 rotation relative to airframe - * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - * - * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * Thrust coefficient of rotor 1 + * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. + * + * + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC2_ROT, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR1_CT, 6.5); /** - * Accelerometer 3 rotation relative to airframe + * Thrust coefficient of rotor 2 * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_INT32(CAL_ACC3_ROT, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR2_CT, 6.5); /** - * Accelerometer 0 X-axis offset + * Thrust coefficient of rotor 3 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR3_CT, 6.5); /** - * Accelerometer 1 X-axis offset + * Thrust coefficient of rotor 4 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR4_CT, 6.5); /** - * Accelerometer 2 X-axis offset + * Thrust coefficient of rotor 5 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR5_CT, 6.5); /** - * Accelerometer 3 X-axis offset + * Thrust coefficient of rotor 6 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR6_CT, 6.5); /** - * Accelerometer 0 Y-axis offset + * Thrust coefficient of rotor 7 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR7_CT, 6.5); /** - * Accelerometer 1 Y-axis offset + * Thrust coefficient of rotor 8 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR8_CT, 6.5); /** - * Accelerometer 2 Y-axis offset + * Thrust coefficient of rotor 9 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR9_CT, 6.5); /** - * Accelerometer 3 Y-axis offset + * Thrust coefficient of rotor 10 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR10_CT, 6.5); /** - * Accelerometer 0 Z-axis offset + * Thrust coefficient of rotor 11 * + * The thrust coefficient if defined as Thrust = CT * u^2, + * where u (with value between actuator minimum and maximum) + * is the output signal sent to the motor controller. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_CT, 6.5); /** - * Accelerometer 1 Z-axis offset + * Moment coefficient of rotor 0 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR0_KM, 0.05); /** - * Accelerometer 2 Z-axis offset + * Moment coefficient of rotor 1 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR1_KM, 0.05); /** - * Accelerometer 3 Z-axis offset + * Moment coefficient of rotor 2 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_ROTOR2_KM, 0.05); /** - * Accelerometer 0 X-axis scaling factor + * Moment coefficient of rotor 3 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_XSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR3_KM, 0.05); /** - * Accelerometer 1 X-axis scaling factor + * Moment coefficient of rotor 4 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_XSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR4_KM, 0.05); /** - * Accelerometer 2 X-axis scaling factor + * Moment coefficient of rotor 5 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_XSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR5_KM, 0.05); /** - * Accelerometer 3 X-axis scaling factor + * Moment coefficient of rotor 6 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_XSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR6_KM, 0.05); /** - * Accelerometer 0 Y-axis scaling factor + * Moment coefficient of rotor 7 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_YSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR7_KM, 0.05); /** - * Accelerometer 1 Y-axis scaling factor + * Moment coefficient of rotor 8 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_YSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR8_KM, 0.05); /** - * Accelerometer 2 Y-axis scaling factor + * Moment coefficient of rotor 9 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_YSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR9_KM, 0.05); /** - * Accelerometer 3 Y-axis scaling factor + * Moment coefficient of rotor 10 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_YSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR10_KM, 0.05); /** - * Accelerometer 0 Z-axis scaling factor + * Moment coefficient of rotor 11 * + * The moment coefficient if defined as Torque = KM * Thrust. + * + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_ZSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_KM, 0.05); /** - * Accelerometer 1 Z-axis scaling factor + * Rotor 0 tilt assignment * - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CA_ROTOR0_TILT, 0); /** - * Accelerometer 2 Z-axis scaling factor + * Rotor 1 tilt assignment * - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CA_ROTOR1_TILT, 0); /** - * Accelerometer 3 Z-axis scaling factor + * Rotor 2 tilt assignment * - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CA_ROTOR2_TILT, 0); /** - * Barometer 0 calibration device ID + * Rotor 3 tilt assignment * - * Device ID of the barometer this calibration applies to. + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @category System + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(CAL_BARO0_ID, 0); +PARAM_DEFINE_INT32(CA_ROTOR3_TILT, 0); /** - * Barometer 1 calibration device ID + * Rotor 4 tilt assignment * - * Device ID of the barometer this calibration applies to. + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @category System + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(CAL_BARO1_ID, 0); +PARAM_DEFINE_INT32(CA_ROTOR4_TILT, 0); /** - * Barometer 2 calibration device ID + * Rotor 5 tilt assignment * - * Device ID of the barometer this calibration applies to. + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @category System + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(CAL_BARO2_ID, 0); +PARAM_DEFINE_INT32(CA_ROTOR5_TILT, 0); /** - * Barometer 3 calibration device ID + * Rotor 6 tilt assignment * - * Device ID of the barometer this calibration applies to. + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @category System + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(CAL_BARO3_ID, 0); +PARAM_DEFINE_INT32(CA_ROTOR6_TILT, 0); /** - * Barometer 0 priority + * Rotor 7 tilt assignment * - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(CAL_BARO0_PRIO, -1); +PARAM_DEFINE_INT32(CA_ROTOR7_TILT, 0); /** - * Barometer 1 priority + * Rotor 8 tilt assignment * - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(CAL_BARO1_PRIO, -1); +PARAM_DEFINE_INT32(CA_ROTOR8_TILT, 0); /** - * Barometer 2 priority + * Rotor 9 tilt assignment * - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(CAL_BARO2_PRIO, -1); +PARAM_DEFINE_INT32(CA_ROTOR9_TILT, 0); /** - * Barometer 3 priority + * Rotor 10 tilt assignment * - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(CAL_BARO3_PRIO, -1); +PARAM_DEFINE_INT32(CA_ROTOR10_TILT, 0); /** - * Barometer 0 offset + * Rotor 11 tilt assignment * - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_FLOAT(CAL_BARO0_OFF, 0.0); +PARAM_DEFINE_INT32(CA_ROTOR11_TILT, 0); /** - * Barometer 1 offset + * Total number of Control Surfaces * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @value 0 0 + * @value 1 1 + * @value 2 2 + * @value 3 3 + * @value 4 4 + * @value 5 5 + * @value 6 6 + * @value 7 7 + * @value 8 8 */ -PARAM_DEFINE_FLOAT(CAL_BARO1_OFF, 0.0); +PARAM_DEFINE_INT32(CA_SV_CS_COUNT, 0); /** - * Barometer 2 offset + * Control Surface 0 type * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @value 0 (Not set) + * @value 1 Left Aileron + * @value 2 Right Aileron + * @value 3 Elevator + * @value 4 Rudder + * @value 5 Left Elevon + * @value 6 Right Elevon + * @value 7 Left V-Tail + * @value 8 Right V-Tail + * @value 9 Left Flap + * @value 10 Right Flap + * @value 11 Airbrake + * @value 12 Custom + * @value 13 Left A-tail + * @value 14 Right A-tail + * @value 15 Single Channel Aileron + * @value 16 Steering Wheel + * @value 17 Left Spoiler + * @value 18 Right Spoiler */ -PARAM_DEFINE_FLOAT(CAL_BARO2_OFF, 0.0); +PARAM_DEFINE_INT32(CA_SV_CS0_TYPE, 0); /** - * Barometer 3 offset + * Control Surface 1 type * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @value 0 (Not set) + * @value 1 Left Aileron + * @value 2 Right Aileron + * @value 3 Elevator + * @value 4 Rudder + * @value 5 Left Elevon + * @value 6 Right Elevon + * @value 7 Left V-Tail + * @value 8 Right V-Tail + * @value 9 Left Flap + * @value 10 Right Flap + * @value 11 Airbrake + * @value 12 Custom + * @value 13 Left A-tail + * @value 14 Right A-tail + * @value 15 Single Channel Aileron + * @value 16 Steering Wheel + * @value 17 Left Spoiler + * @value 18 Right Spoiler */ -PARAM_DEFINE_FLOAT(CAL_BARO3_OFF, 0.0); +PARAM_DEFINE_INT32(CA_SV_CS1_TYPE, 0); /** - * Gyroscope 0 calibration device ID + * Control Surface 2 type * - * Device ID of the gyroscope this calibration applies to. + * * - * @group Sensor Calibration - * @category System + * @group Geometry + * @value 0 (Not set) + * @value 1 Left Aileron + * @value 2 Right Aileron + * @value 3 Elevator + * @value 4 Rudder + * @value 5 Left Elevon + * @value 6 Right Elevon + * @value 7 Left V-Tail + * @value 8 Right V-Tail + * @value 9 Left Flap + * @value 10 Right Flap + * @value 11 Airbrake + * @value 12 Custom + * @value 13 Left A-tail + * @value 14 Right A-tail + * @value 15 Single Channel Aileron + * @value 16 Steering Wheel + * @value 17 Left Spoiler + * @value 18 Right Spoiler */ -PARAM_DEFINE_INT32(CAL_GYRO0_ID, 0); +PARAM_DEFINE_INT32(CA_SV_CS2_TYPE, 0); /** - * Gyroscope 1 calibration device ID + * Control Surface 3 type * - * Device ID of the gyroscope this calibration applies to. + * * - * @group Sensor Calibration - * @category System + * @group Geometry + * @value 0 (Not set) + * @value 1 Left Aileron + * @value 2 Right Aileron + * @value 3 Elevator + * @value 4 Rudder + * @value 5 Left Elevon + * @value 6 Right Elevon + * @value 7 Left V-Tail + * @value 8 Right V-Tail + * @value 9 Left Flap + * @value 10 Right Flap + * @value 11 Airbrake + * @value 12 Custom + * @value 13 Left A-tail + * @value 14 Right A-tail + * @value 15 Single Channel Aileron + * @value 16 Steering Wheel + * @value 17 Left Spoiler + * @value 18 Right Spoiler */ -PARAM_DEFINE_INT32(CAL_GYRO1_ID, 0); +PARAM_DEFINE_INT32(CA_SV_CS3_TYPE, 0); /** - * Gyroscope 2 calibration device ID + * Control Surface 4 type * - * Device ID of the gyroscope this calibration applies to. + * * - * @group Sensor Calibration - * @category System + * @group Geometry + * @value 0 (Not set) + * @value 1 Left Aileron + * @value 2 Right Aileron + * @value 3 Elevator + * @value 4 Rudder + * @value 5 Left Elevon + * @value 6 Right Elevon + * @value 7 Left V-Tail + * @value 8 Right V-Tail + * @value 9 Left Flap + * @value 10 Right Flap + * @value 11 Airbrake + * @value 12 Custom + * @value 13 Left A-tail + * @value 14 Right A-tail + * @value 15 Single Channel Aileron + * @value 16 Steering Wheel + * @value 17 Left Spoiler + * @value 18 Right Spoiler */ -PARAM_DEFINE_INT32(CAL_GYRO2_ID, 0); +PARAM_DEFINE_INT32(CA_SV_CS4_TYPE, 0); /** - * Gyroscope 3 calibration device ID + * Control Surface 5 type * - * Device ID of the gyroscope this calibration applies to. + * * - * @group Sensor Calibration - * @category System + * @group Geometry + * @value 0 (Not set) + * @value 1 Left Aileron + * @value 2 Right Aileron + * @value 3 Elevator + * @value 4 Rudder + * @value 5 Left Elevon + * @value 6 Right Elevon + * @value 7 Left V-Tail + * @value 8 Right V-Tail + * @value 9 Left Flap + * @value 10 Right Flap + * @value 11 Airbrake + * @value 12 Custom + * @value 13 Left A-tail + * @value 14 Right A-tail + * @value 15 Single Channel Aileron + * @value 16 Steering Wheel + * @value 17 Left Spoiler + * @value 18 Right Spoiler */ -PARAM_DEFINE_INT32(CAL_GYRO3_ID, 0); +PARAM_DEFINE_INT32(CA_SV_CS5_TYPE, 0); /** - * Gyroscope 0 priority + * Control Surface 6 type * * * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @value 0 (Not set) + * @value 1 Left Aileron + * @value 2 Right Aileron + * @value 3 Elevator + * @value 4 Rudder + * @value 5 Left Elevon + * @value 6 Right Elevon + * @value 7 Left V-Tail + * @value 8 Right V-Tail + * @value 9 Left Flap + * @value 10 Right Flap + * @value 11 Airbrake + * @value 12 Custom + * @value 13 Left A-tail + * @value 14 Right A-tail + * @value 15 Single Channel Aileron + * @value 16 Steering Wheel + * @value 17 Left Spoiler + * @value 18 Right Spoiler */ -PARAM_DEFINE_INT32(CAL_GYRO0_PRIO, -1); +PARAM_DEFINE_INT32(CA_SV_CS6_TYPE, 0); /** - * Gyroscope 1 priority + * Control Surface 7 type * * * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @value 0 (Not set) + * @value 1 Left Aileron + * @value 2 Right Aileron + * @value 3 Elevator + * @value 4 Rudder + * @value 5 Left Elevon + * @value 6 Right Elevon + * @value 7 Left V-Tail + * @value 8 Right V-Tail + * @value 9 Left Flap + * @value 10 Right Flap + * @value 11 Airbrake + * @value 12 Custom + * @value 13 Left A-tail + * @value 14 Right A-tail + * @value 15 Single Channel Aileron + * @value 16 Steering Wheel + * @value 17 Left Spoiler + * @value 18 Right Spoiler */ -PARAM_DEFINE_INT32(CAL_GYRO1_PRIO, -1); +PARAM_DEFINE_INT32(CA_SV_CS7_TYPE, 0); /** - * Gyroscope 2 priority + * Control Surface 0 roll torque scaling * * * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_GYRO2_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_R, 0.0); /** - * Gyroscope 3 priority + * Control Surface 1 roll torque scaling * * * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_GYRO3_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_R, 0.0); /** - * Gyroscope 0 rotation relative to airframe + * Control Surface 2 roll torque scaling * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_GYRO0_ROT, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_R, 0.0); /** - * Gyroscope 1 rotation relative to airframe + * Control Surface 3 roll torque scaling * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_GYRO1_ROT, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_R, 0.0); /** - * Gyroscope 2 rotation relative to airframe + * Control Surface 4 roll torque scaling * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_GYRO2_ROT, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_R, 0.0); /** - * Gyroscope 3 rotation relative to airframe + * Control Surface 5 roll torque scaling * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. * * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_GYRO3_ROT, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_R, 0.0); /** - * Gyroscope 0 X-axis offset + * Control Surface 6 roll torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO0_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_R, 0.0); /** - * Gyroscope 1 X-axis offset + * Control Surface 7 roll torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO1_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_R, 0.0); /** - * Gyroscope 2 X-axis offset + * Control Surface 0 pitch torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO2_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_P, 0.0); /** - * Gyroscope 3 X-axis offset + * Control Surface 1 pitch torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO3_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_P, 0.0); /** - * Gyroscope 0 Y-axis offset + * Control Surface 2 pitch torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_P, 0.0); /** - * Gyroscope 1 Y-axis offset + * Control Surface 3 pitch torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_P, 0.0); /** - * Gyroscope 2 Y-axis offset + * Control Surface 4 pitch torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_P, 0.0); /** - * Gyroscope 3 Y-axis offset + * Control Surface 5 pitch torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO3_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_P, 0.0); /** - * Gyroscope 0 Z-axis offset + * Control Surface 6 pitch torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_P, 0.0); /** - * Gyroscope 1 Z-axis offset + * Control Surface 7 pitch torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_P, 0.0); /** - * Gyroscope 2 Z-axis offset + * Control Surface 0 yaw torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_Y, 0.0); /** - * Gyroscope 3 Z-axis offset + * Control Surface 1 yaw torque scaling * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit rad/s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO3_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_Y, 0.0); /** - * Magnetometer 0 calibration device ID + * Control Surface 2 yaw torque scaling * - * Device ID of the magnetometer this calibration applies to. + * * - * @group Sensor Calibration - * @category System + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_MAG0_ID, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_Y, 0.0); /** - * Magnetometer 1 calibration device ID + * Control Surface 3 yaw torque scaling * - * Device ID of the magnetometer this calibration applies to. + * * - * @group Sensor Calibration - * @category System + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_MAG1_ID, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_Y, 0.0); /** - * Magnetometer 2 calibration device ID + * Control Surface 4 yaw torque scaling * - * Device ID of the magnetometer this calibration applies to. + * * - * @group Sensor Calibration - * @category System + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_MAG2_ID, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_Y, 0.0); /** - * Magnetometer 3 calibration device ID + * Control Surface 5 yaw torque scaling * - * Device ID of the magnetometer this calibration applies to. + * * - * @group Sensor Calibration - * @category System + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_MAG3_ID, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_Y, 0.0); /** - * Magnetometer 0 priority + * Control Surface 6 yaw torque scaling * * * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_MAG0_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_Y, 0.0); /** - * Magnetometer 1 priority + * Control Surface 7 yaw torque scaling * * * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(CAL_MAG1_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_Y, 0.0); /** - * Magnetometer 2 priority + * Control Surface 0 trim * - * + * Can be used to add an offset to the servo control. * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_INT32(CAL_MAG2_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS0_TRIM, 0.0); /** - * Magnetometer 3 priority + * Control Surface 1 trim * - * + * Can be used to add an offset to the servo control. * - * @group Sensor Calibration - * @value -1 Uninitialized - * @value 0 Disabled - * @value 1 Min - * @value 25 Low - * @value 50 Medium (Default) - * @value 75 High - * @value 100 Max - * @category System + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_INT32(CAL_MAG3_PRIO, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS1_TRIM, 0.0); /** - * Magnetometer 0 rotation relative to airframe + * Control Surface 2 trim * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - * + * Can be used to add an offset to the servo control. * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_INT32(CAL_MAG0_ROT, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS2_TRIM, 0.0); /** - * Magnetometer 1 rotation relative to airframe + * Control Surface 3 trim * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - * + * Can be used to add an offset to the servo control. * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_INT32(CAL_MAG1_ROT, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS3_TRIM, 0.0); /** - * Magnetometer 2 rotation relative to airframe - * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - * + * Control Surface 4 trim * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * Can be used to add an offset to the servo control. + * + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_INT32(CAL_MAG2_ROT, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS4_TRIM, 0.0); /** - * Magnetometer 3 rotation relative to airframe + * Control Surface 5 trim * - * An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - * + * Can be used to add an offset to the servo control. * - * @group Sensor Calibration - * @value -1 Internal - * @value 0 No rotation - * @value 1 Yaw 45° - * @value 2 Yaw 90° - * @value 3 Yaw 135° - * @value 4 Yaw 180° - * @value 5 Yaw 225° - * @value 6 Yaw 270° - * @value 7 Yaw 315° - * @value 8 Roll 180° - * @value 9 Roll 180°, Yaw 45° - * @value 10 Roll 180°, Yaw 90° - * @value 11 Roll 180°, Yaw 135° - * @value 12 Pitch 180° - * @value 13 Roll 180°, Yaw 225° - * @value 14 Roll 180°, Yaw 270° - * @value 15 Roll 180°, Yaw 315° - * @value 16 Roll 90° - * @value 17 Roll 90°, Yaw 45° - * @value 18 Roll 90°, Yaw 90° - * @value 19 Roll 90°, Yaw 135° - * @value 20 Roll 270° - * @value 21 Roll 270°, Yaw 45° - * @value 22 Roll 270°, Yaw 90° - * @value 23 Roll 270°, Yaw 135° - * @value 24 Pitch 90° - * @value 25 Pitch 270° - * @value 26 Pitch 180°, Yaw 90° - * @value 27 Pitch 180°, Yaw 270° - * @value 28 Roll 90°, Pitch 90° - * @value 29 Roll 180°, Pitch 90° - * @value 30 Roll 270°, Pitch 90° - * @value 31 Roll 90°, Pitch 180° - * @value 32 Roll 270°, Pitch 180° - * @value 33 Roll 90°, Pitch 270° - * @value 34 Roll 180°, Pitch 270° - * @value 35 Roll 270°, Pitch 270° - * @value 36 Roll 90°, Pitch 180°, Yaw 90° - * @value 37 Roll 90°, Yaw 270° - * @value 38 Roll 90°, Pitch 68°, Yaw 293° - * @value 39 Pitch 315° - * @value 40 Roll 90°, Pitch 315° - * @category System - * @min -1 - * @max 40 + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_INT32(CAL_MAG3_ROT, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS5_TRIM, 0.0); /** - * Magnetometer 0 X-axis offset + * Control Surface 6 trim * - * + * Can be used to add an offset to the servo control. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_TRIM, 0.0); /** - * Magnetometer 1 X-axis offset + * Control Surface 7 trim + * + * Can be used to add an offset to the servo control. + * + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 + */ +PARAM_DEFINE_FLOAT(CA_SV_CS7_TRIM, 0.0); + +/** + * Control Surface 0 configuration as flap * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS0_FLAP, 0); /** - * Magnetometer 2 X-axis offset + * Control Surface 1 configuration as flap * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_FLAP, 0); /** - * Magnetometer 3 X-axis offset + * Control Surface 2 configuration as flap * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_FLAP, 0); /** - * Magnetometer 0 Y-axis offset + * Control Surface 3 configuration as flap * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_FLAP, 0); /** - * Magnetometer 1 Y-axis offset + * Control Surface 4 configuration as flap * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_FLAP, 0); /** - * Magnetometer 2 Y-axis offset + * Control Surface 5 configuration as flap * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_FLAP, 0); /** - * Magnetometer 3 Y-axis offset + * Control Surface 6 configuration as flap * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_FLAP, 0); /** - * Magnetometer 0 Z-axis offset + * Control Surface 7 configuration as flap * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_FLAP, 0); /** - * Magnetometer 1 Z-axis offset + * Control Surface 0 configuration as spoiler * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS0_SPOIL, 0); /** - * Magnetometer 2 Z-axis offset + * Control Surface 1 configuration as spoiler * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_SPOIL, 0); /** - * Magnetometer 3 Z-axis offset + * Control Surface 2 configuration as spoiler * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit gauss + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_SPOIL, 0); /** - * Magnetometer 0 X-axis scaling factor + * Control Surface 3 configuration as spoiler * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_XSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_SPOIL, 0); /** - * Magnetometer 1 X-axis scaling factor + * Control Surface 4 configuration as spoiler * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_XSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_SPOIL, 0); /** - * Magnetometer 2 X-axis scaling factor + * Control Surface 5 configuration as spoiler * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_XSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_SPOIL, 0); /** - * Magnetometer 3 X-axis scaling factor + * Control Surface 6 configuration as spoiler * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_XSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_SPOIL, 0); /** - * Magnetometer 0 Y-axis scaling factor + * Control Surface 7 configuration as spoiler * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_YSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_SPOIL, 0); /** - * Magnetometer 1 Y-axis scaling factor + * Total number of Tilt Servos * * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @value 0 0 + * @value 1 1 + * @value 2 2 + * @value 3 3 + * @value 4 4 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_YSCALE, 1.0); +PARAM_DEFINE_INT32(CA_SV_TL_COUNT, 0); /** - * Magnetometer 2 Y-axis scaling factor + * Tilt 0 is used for control * - * + * Define if this servo is used for additional control. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @value 0 None + * @value 1 Yaw + * @value 2 Pitch + * @value 3 Yaw and Pitch */ -PARAM_DEFINE_FLOAT(CAL_MAG2_YSCALE, 1.0); +PARAM_DEFINE_INT32(CA_SV_TL0_CT, 1); /** - * Magnetometer 3 Y-axis scaling factor + * Tilt 1 is used for control * - * + * Define if this servo is used for additional control. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @value 0 None + * @value 1 Yaw + * @value 2 Pitch + * @value 3 Yaw and Pitch */ -PARAM_DEFINE_FLOAT(CAL_MAG3_YSCALE, 1.0); +PARAM_DEFINE_INT32(CA_SV_TL1_CT, 1); /** - * Magnetometer 0 Z-axis scaling factor + * Tilt 2 is used for control * - * + * Define if this servo is used for additional control. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @value 0 None + * @value 1 Yaw + * @value 2 Pitch + * @value 3 Yaw and Pitch */ -PARAM_DEFINE_FLOAT(CAL_MAG0_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CA_SV_TL2_CT, 1); /** - * Magnetometer 1 Z-axis scaling factor + * Tilt 3 is used for control * - * + * Define if this servo is used for additional control. * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @value 0 None + * @value 1 Yaw + * @value 2 Pitch + * @value 3 Yaw and Pitch */ -PARAM_DEFINE_FLOAT(CAL_MAG1_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CA_SV_TL3_CT, 1); /** - * Magnetometer 2 Z-axis scaling factor + * Tilt Servo 0 Tilt Angle at Minimum * + * Defines the tilt angle when the servo is at the minimum. + * An angle of zero means upwards. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG2_ZSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_SV_TL0_MINA, 0.0); /** - * Magnetometer 3 Z-axis scaling factor + * Tilt Servo 1 Tilt Angle at Minimum * + * Defines the tilt angle when the servo is at the minimum. + * An angle of zero means upwards. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Geometry + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG3_ZSCALE, 1.0); +PARAM_DEFINE_FLOAT(CA_SV_TL1_MINA, 0.0); /** - * Magnetometer 0 X-axis off diagonal scale factor + * Tilt Servo 2 Tilt Angle at Minimum * + * Defines the tilt angle when the servo is at the minimum. + * An angle of zero means upwards. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG0_XODIAG, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL2_MINA, 0.0); /** - * Magnetometer 1 X-axis off diagonal scale factor + * Tilt Servo 3 Tilt Angle at Minimum * + * Defines the tilt angle when the servo is at the minimum. + * An angle of zero means upwards. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG1_XODIAG, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL3_MINA, 0.0); /** - * Magnetometer 2 X-axis off diagonal scale factor + * Tilt Servo 0 Tilt Angle at Maximum * + * Defines the tilt angle when the servo is at the maximum. + * An angle of zero means upwards. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG2_XODIAG, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL0_MAXA, 90.0); /** - * Magnetometer 3 X-axis off diagonal scale factor + * Tilt Servo 1 Tilt Angle at Maximum * + * Defines the tilt angle when the servo is at the maximum. + * An angle of zero means upwards. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG3_XODIAG, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL1_MAXA, 90.0); /** - * Magnetometer 0 Y-axis off diagonal scale factor + * Tilt Servo 2 Tilt Angle at Maximum * + * Defines the tilt angle when the servo is at the maximum. + * An angle of zero means upwards. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG0_YODIAG, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL2_MAXA, 90.0); /** - * Magnetometer 1 Y-axis off diagonal scale factor + * Tilt Servo 3 Tilt Angle at Maximum * + * Defines the tilt angle when the servo is at the maximum. + * An angle of zero means upwards. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG1_YODIAG, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL3_MAXA, 90.0); /** - * Magnetometer 2 Y-axis off diagonal scale factor + * Tilt Servo 0 Tilt Direction * + * Defines the direction the servo tilts towards when moving towards the maximum tilt angle. + * For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', + * the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @value 0 Towards Front + * @value 90 Towards Right + * @min 0 + * @max 359 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_YODIAG, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL0_TD, 0); /** - * Magnetometer 3 Y-axis off diagonal scale factor + * Tilt Servo 1 Tilt Direction * + * Defines the direction the servo tilts towards when moving towards the maximum tilt angle. + * For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', + * the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @value 0 Towards Front + * @value 90 Towards Right + * @min 0 + * @max 359 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_YODIAG, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL1_TD, 0); /** - * Magnetometer 0 Z-axis off diagonal scale factor + * Tilt Servo 2 Tilt Direction * + * Defines the direction the servo tilts towards when moving towards the maximum tilt angle. + * For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', + * the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. * * - * @group Sensor Calibration - * @category System - * @volatile True + * @group Geometry + * @value 0 Towards Front + * @value 90 Towards Right + * @min 0 + * @max 359 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_ZODIAG, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL2_TD, 0); /** - * Magnetometer 1 Z-axis off diagonal scale factor + * Tilt Servo 3 Tilt Direction * + * Defines the direction the servo tilts towards when moving towards the maximum tilt angle. + * For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', + * the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. * * - * @group Sensor Calibration - * @category System - * @volatile True + * @group Geometry + * @value 0 Towards Front + * @value 90 Towards Right + * @min 0 + * @max 359 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_ZODIAG, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL3_TD, 0); /** - * Magnetometer 2 Z-axis off diagonal scale factor + * Number of swash plates servos * * * - * @group Sensor Calibration - * @category System - * @volatile True + * @group Geometry + * @value 3 3 + * @value 4 4 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_ZODIAG, 0.0); +PARAM_DEFINE_INT32(CA_SP0_COUNT, 3); /** - * Magnetometer 3 Z-axis off diagonal scale factor + * Angle for swash plate servo 0 * + * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). * * - * @group Sensor Calibration - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @increment 10 + * @min 0 + * @max 360 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG3_ZODIAG, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ANG0, 0); /** - * Magnetometer 0 X Axis throttle compensation + * Angle for swash plate servo 1 * - * Coefficient describing linear relationship between - * X component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @increment 10 + * @min 0 + * @max 360 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG0_XCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ANG1, 140); /** - * Magnetometer 1 X Axis throttle compensation + * Angle for swash plate servo 2 * - * Coefficient describing linear relationship between - * X component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @increment 10 + * @min 0 + * @max 360 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG1_XCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ANG2, 220); /** - * Magnetometer 2 X Axis throttle compensation + * Angle for swash plate servo 3 * - * Coefficient describing linear relationship between - * X component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Geometry + * @decimal 0 + * @increment 10 + * @min 0 + * @max 360 + * @unit deg */ -PARAM_DEFINE_FLOAT(CAL_MAG2_XCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ANG3, 0); /** - * Magnetometer 3 X Axis throttle compensation + * Arm length for swash plate servo 0 * - * Coefficient describing linear relationship between - * X component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * This is relative to the other arm lengths. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_XCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ARM_L0, 1.0); /** - * Magnetometer 0 Y Axis throttle compensation + * Arm length for swash plate servo 1 * - * Coefficient describing linear relationship between - * Y component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * This is relative to the other arm lengths. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_YCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ARM_L1, 1.0); /** - * Magnetometer 1 Y Axis throttle compensation + * Arm length for swash plate servo 2 * - * Coefficient describing linear relationship between - * Y component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * This is relative to the other arm lengths. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_YCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ARM_L2, 1.0); /** - * Magnetometer 2 Y Axis throttle compensation + * Arm length for swash plate servo 3 * - * Coefficient describing linear relationship between - * Y component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * This is relative to the other arm lengths. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_YCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ARM_L3, 1.0); /** - * Magnetometer 3 Y Axis throttle compensation + * Throttle curve at position 0 * - * Coefficient describing linear relationship between - * Y component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * Defines the output throttle at the interval position 0. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_YCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C0, 1); /** - * Magnetometer 0 Z Axis throttle compensation + * Throttle curve at position 1 * - * Coefficient describing linear relationship between - * Z component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * Defines the output throttle at the interval position 1. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_ZCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C1, 1); -/** - * Magnetometer 1 Z Axis throttle compensation - * - * Coefficient describing linear relationship between - * Z component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] +/** + * Throttle curve at position 2 + * + * Defines the output throttle at the interval position 2. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_ZCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C2, 1); /** - * Magnetometer 2 Z Axis throttle compensation + * Throttle curve at position 3 * - * Coefficient describing linear relationship between - * Z component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * Defines the output throttle at the interval position 3. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_ZCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C3, 1); /** - * Magnetometer 3 Z Axis throttle compensation + * Throttle curve at position 4 * - * Coefficient describing linear relationship between - * Z component of magnetometer in body frame axis - * and either current or throttle depending on value of CAL_MAG_COMP_TYP. - * Unit for throttle-based compensation is [G] and - * for current-based compensation [G/kA] + * Defines the output throttle at the interval position 4. * * - * @group Sensor Calibration + * @group Geometry * @decimal 3 - * @category System - * @volatile True + * @increment 0.1 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_ZCOMP, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C4, 1); /** - * HIL Channel 1 Output Function + * Collective pitch curve at position 0 * - * Select what should be output on HIL Channel 1. + * Defines the collective pitch at the interval position 0 for a given thrust setpoint. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * Use negative values if the swash plate needs to move down to provide upwards thrust. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @decimal 3 + * @increment 0.1 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC1, 0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C0, -0.05); /** - * HIL Channel 2 Output Function + * Collective pitch curve at position 1 * - * Select what should be output on HIL Channel 2. + * Defines the collective pitch at the interval position 1 for a given thrust setpoint. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * Use negative values if the swash plate needs to move down to provide upwards thrust. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @decimal 3 + * @increment 0.1 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC2, 0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C1, 0.0725); /** - * HIL Channel 3 Output Function + * Collective pitch curve at position 2 * - * Select what should be output on HIL Channel 3. + * Defines the collective pitch at the interval position 2 for a given thrust setpoint. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * Use negative values if the swash plate needs to move down to provide upwards thrust. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @decimal 3 + * @increment 0.1 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC3, 0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C2, 0.2); /** - * HIL Channel 4 Output Function + * Collective pitch curve at position 3 * - * Select what should be output on HIL Channel 4. + * Defines the collective pitch at the interval position 3 for a given thrust setpoint. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * Use negative values if the swash plate needs to move down to provide upwards thrust. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @decimal 3 + * @increment 0.1 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC4, 0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C3, 0.325); /** - * HIL Channel 5 Output Function + * Collective pitch curve at position 4 * - * Select what should be output on HIL Channel 5. + * Defines the collective pitch at the interval position 4 for a given thrust setpoint. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * Use negative values if the swash plate needs to move down to provide upwards thrust. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @decimal 3 + * @increment 0.1 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC5, 0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C4, 0.45); /** - * HIL Channel 6 Output Function + * Scale for yaw compensation based on collective pitch * - * Select what should be output on HIL Channel 6. + * This allows to add a proportional factor of the collective pitch command to the yaw command. + * A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O) * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @decimal 3 + * @increment 0.1 + * @min -2 + * @max 2 */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC6, 0); +PARAM_DEFINE_FLOAT(CA_HELI_YAW_CP_S, 0.0); /** - * HIL Channel 7 Output Function + * Offset for yaw compensation based on collective pitch * - * Select what should be output on HIL Channel 7. + * This allows to specify which collective pitch command results in the least amount of rotor drag. + * This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch + * by aligning the lowest rotor drag with zero compensation. + * For symmetric profile blades this is the command that results in exactly 0° collective blade angle. + * For lift profile blades this is typically a command resulting in slightly negative collective blade angle. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O) * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @decimal 3 + * @increment 0.1 + * @min -2 + * @max 2 */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC7, 0); +PARAM_DEFINE_FLOAT(CA_HELI_YAW_CP_O, 0.0); /** - * HIL Channel 8 Output Function + * Scale for yaw compensation based on throttle * - * Select what should be output on HIL Channel 8. + * This allows to add a proportional factor of the throttle command to the yaw command. + * A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * tail_output += CA_HELI_YAW_TH_S * throttle * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @decimal 3 + * @increment 0.1 + * @min -2 + * @max 2 */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC8, 0); +PARAM_DEFINE_FLOAT(CA_HELI_YAW_TH_S, 0.0); /** - * HIL Channel 9 Output Function + * Main rotor turns counter-clockwise * - * Select what should be output on HIL Channel 9. + * Default configuration is for a clockwise turning main rotor and + * positive thrust of the tail rotor is expected to rotate the vehicle clockwise. + * Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction + * which is mostly the case when the main rotor turns counter-clockwise. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * + * @group Geometry + * @boolean + */ +PARAM_DEFINE_INT32(CA_HELI_YAW_CCW, 0); + +/** + * Motor failure handling mode + * + * This is used to specify how to handle motor failures + * reported by failure detector. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Geometry + * @value 0 Ignore + * @value 1 Remove first failed motor from effectiveness */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC9, 0); +PARAM_DEFINE_INT32(CA_FAILURE_MODE, 0); /** - * HIL Channel 10 Output Function + * Empty cell voltage (5C load) * - * Select what should be output on HIL Channel 10. + * Defines the voltage where a single cell of battery 1 is considered empty. + * The voltage should be chosen before the steep dropoff to 2.8V. A typical + * lithium battery can only be discharged down to 10% before it drops off + * to a voltage level damaging the cells. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * + * @group Battery Calibration + * @decimal 2 + * @increment 0.01 + * @unit V + * @reboot_required True + */ +PARAM_DEFINE_FLOAT(BAT1_V_EMPTY, 3.6); + +/** + * Empty cell voltage (5C load) + * + * Defines the voltage where a single cell of battery 1 is considered empty. + * The voltage should be chosen before the steep dropoff to 2.8V. A typical + * lithium battery can only be discharged down to 10% before it drops off + * to a voltage level damaging the cells. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Battery Calibration + * @decimal 2 + * @increment 0.01 + * @unit V + * @reboot_required True + */ +PARAM_DEFINE_FLOAT(BAT2_V_EMPTY, 3.6); + +/** + * Full cell voltage (5C load) + * + * Defines the voltage where a single cell of battery 1 is considered full + * under a mild load. This will never be the nominal voltage of 4.2V + * + * + * @group Battery Calibration + * @decimal 2 + * @increment 0.01 + * @unit V + * @reboot_required True + */ +PARAM_DEFINE_FLOAT(BAT1_V_CHARGED, 4.05); + +/** + * Full cell voltage (5C load) + * + * Defines the voltage where a single cell of battery 1 is considered full + * under a mild load. This will never be the nominal voltage of 4.2V + * + * + * @group Battery Calibration + * @decimal 2 + * @increment 0.01 + * @unit V + * @reboot_required True */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC10, 0); +PARAM_DEFINE_FLOAT(BAT2_V_CHARGED, 4.05); /** - * HIL Channel 11 Output Function + * Voltage drop per cell on full throttle * - * Select what should be output on HIL Channel 11. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * This implicitly defines the internal resistance + * to maximum current ratio for battery 1 and assumes linearity. + * A good value to use is the difference between the + * 5C and 20-25C load. Not used if BAT1_R_INTERNAL is + * set. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Battery Calibration + * @decimal 2 + * @increment 0.01 + * @min 0.07 + * @max 0.5 + * @unit V + * @reboot_required True */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC11, 0); +PARAM_DEFINE_FLOAT(BAT1_V_LOAD_DROP, 0.1); /** - * HIL Channel 12 Output Function + * Voltage drop per cell on full throttle * - * Select what should be output on HIL Channel 12. + * This implicitly defines the internal resistance + * to maximum current ratio for battery 1 and assumes linearity. + * A good value to use is the difference between the + * 5C and 20-25C load. Not used if BAT2_R_INTERNAL is + * set. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * + * @group Battery Calibration + * @decimal 2 + * @increment 0.01 + * @min 0.07 + * @max 0.5 + * @unit V + * @reboot_required True + */ +PARAM_DEFINE_FLOAT(BAT2_V_LOAD_DROP, 0.1); + +/** + * Explicitly defines the per cell internal resistance for battery 1 + * + * If non-negative, then this will be used in place of + * BAT1_V_LOAD_DROP for all calculations. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Battery Calibration + * @decimal 4 + * @increment 0.0005 + * @min -1.0 + * @max 0.2 + * @unit Ohm + * @reboot_required True */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC12, 0); +PARAM_DEFINE_FLOAT(BAT1_R_INTERNAL, 0.005); /** - * HIL Channel 13 Output Function + * Explicitly defines the per cell internal resistance for battery 2 * - * Select what should be output on HIL Channel 13. + * If non-negative, then this will be used in place of + * BAT2_V_LOAD_DROP for all calculations. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * + * @group Battery Calibration + * @decimal 4 + * @increment 0.0005 + * @min -1.0 + * @max 0.2 + * @unit Ohm + * @reboot_required True + */ +PARAM_DEFINE_FLOAT(BAT2_R_INTERNAL, 0.005); + +/** + * Number of cells for battery 1. + * + * Defines the number of cells the attached battery consists of. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Battery Calibration + * @value 1 1S Battery + * @value 2 2S Battery + * @value 3 3S Battery + * @value 4 4S Battery + * @value 5 5S Battery + * @value 6 6S Battery + * @value 7 7S Battery + * @value 8 8S Battery + * @value 9 9S Battery + * @value 10 10S Battery + * @value 11 11S Battery + * @value 12 12S Battery + * @value 13 13S Battery + * @value 14 14S Battery + * @value 15 15S Battery + * @value 16 16S Battery + * @reboot_required True */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC13, 0); +PARAM_DEFINE_INT32(BAT1_N_CELLS, 0); /** - * HIL Channel 14 Output Function + * Number of cells for battery 2. * - * Select what should be output on HIL Channel 14. - * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * Defines the number of cells the attached battery consists of. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Battery Calibration + * @value 1 1S Battery + * @value 2 2S Battery + * @value 3 3S Battery + * @value 4 4S Battery + * @value 5 5S Battery + * @value 6 6S Battery + * @value 7 7S Battery + * @value 8 8S Battery + * @value 9 9S Battery + * @value 10 10S Battery + * @value 11 11S Battery + * @value 12 12S Battery + * @value 13 13S Battery + * @value 14 14S Battery + * @value 15 15S Battery + * @value 16 16S Battery + * @reboot_required True */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC14, 0); +PARAM_DEFINE_INT32(BAT2_N_CELLS, 0); /** - * HIL Channel 15 Output Function + * Battery 1 capacity. * - * Select what should be output on HIL Channel 15. + * Defines the capacity of battery 1 in mAh. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * + * @group Battery Calibration + * @decimal 0 + * @increment 50 + * @min -1.0 + * @max 100000 + * @unit mAh + * @reboot_required True + */ +PARAM_DEFINE_FLOAT(BAT1_CAPACITY, -1.0); + +/** + * Battery 2 capacity. + * + * Defines the capacity of battery 2 in mAh. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Battery Calibration + * @decimal 0 + * @increment 50 + * @min -1.0 + * @max 100000 + * @unit mAh + * @reboot_required True */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC15, 0); +PARAM_DEFINE_FLOAT(BAT2_CAPACITY, -1.0); /** - * HIL Channel 16 Output Function + * Battery 1 monitoring source. * - * Select what should be output on HIL Channel 16. + * This parameter controls the source of battery data. The value 'Power Module' + * means that measurements are expected to come from a power module. If the value is set to + * 'External' then the system expects to receive mavlink battery status messages. + * If the value is set to 'ESCs', the battery information are taken from the esc_status message. + * This requires the ESC to provide both voltage as well as current. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * + * @group Battery Calibration + * @value -1 Disabled + * @value 0 Power Module + * @value 1 External + * @value 2 ESCs + * @reboot_required True + */ +PARAM_DEFINE_INT32(BAT1_SOURCE, 0); + +/** + * Battery 2 monitoring source. + * + * This parameter controls the source of battery data. The value 'Power Module' + * means that measurements are expected to come from a power module. If the value is set to + * 'External' then the system expects to receive mavlink battery status messages. + * If the value is set to 'ESCs', the battery information are taken from the esc_status message. + * This requires the ESC to provide both voltage as well as current. * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group Battery Calibration + * @value -1 Disabled + * @value 0 Power Module + * @value 1 External + * @value 2 ESCs + * @reboot_required True + */ +PARAM_DEFINE_INT32(BAT2_SOURCE, -1); + +/** + * uXRCE-DDS domain ID + * + * uXRCE-DDS domain ID + * + * @group UXRCE-DDS Client + * @category System + * @reboot_required True */ -PARAM_DEFINE_INT32(HIL_ACT_FUNC16, 0); +PARAM_DEFINE_INT32(UXRCE_DDS_DOM_ID, 0); /** - * Reverse Output Range for HIL + * uXRCE-DDS Session key * - * Allows to reverse the output range for each channel. - * Note: this is only useful for servos. + * uXRCE-DDS key, must be different from zero. + * In a single agent - multi client configuration, each client + * must have a unique session key. * * - * @group Actuator Outputs - * @bit 0 HIL Channel 1 - * @bit 1 HIL Channel 2 - * @bit 2 HIL Channel 3 - * @bit 3 HIL Channel 4 - * @bit 4 HIL Channel 5 - * @bit 5 HIL Channel 6 - * @bit 6 HIL Channel 7 - * @bit 7 HIL Channel 8 - * @bit 8 HIL Channel 9 - * @bit 9 HIL Channel 10 - * @bit 10 HIL Channel 11 - * @bit 11 HIL Channel 12 - * @bit 12 HIL Channel 13 - * @bit 13 HIL Channel 14 - * @bit 14 HIL Channel 15 - * @bit 15 HIL Channel 16 - * @min 0 - * @max 65535 + * @group UXRCE-DDS Client + * @category System + * @reboot_required True */ -PARAM_DEFINE_INT32(HIL_ACT_REV, 0); +PARAM_DEFINE_INT32(UXRCE_DDS_KEY, 1); /** - * UAVCAN ESC 1 Output Function + * SIM_GZ ESC 1 Output Function * - * Select what should be output on UAVCAN ESC 1. + * Select what should be output on SIM_GZ ESC 1. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -9382,12 +8998,12 @@ PARAM_DEFINE_INT32(HIL_ACT_REV, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC1, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC1, 0); /** - * UAVCAN ESC 2 Output Function + * SIM_GZ ESC 2 Output Function * - * Select what should be output on UAVCAN ESC 2. + * Select what should be output on SIM_GZ ESC 2. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -9446,12 +9062,12 @@ PARAM_DEFINE_INT32(UAVCAN_EC_FUNC1, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC2, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC2, 0); /** - * UAVCAN ESC 3 Output Function + * SIM_GZ ESC 3 Output Function * - * Select what should be output on UAVCAN ESC 3. + * Select what should be output on SIM_GZ ESC 3. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -9510,12 +9126,12 @@ PARAM_DEFINE_INT32(UAVCAN_EC_FUNC2, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC3, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC3, 0); /** - * UAVCAN ESC 4 Output Function + * SIM_GZ ESC 4 Output Function * - * Select what should be output on UAVCAN ESC 4. + * Select what should be output on SIM_GZ ESC 4. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -9574,12 +9190,12 @@ PARAM_DEFINE_INT32(UAVCAN_EC_FUNC3, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC4, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC4, 0); /** - * UAVCAN ESC 5 Output Function + * SIM_GZ ESC 5 Output Function * - * Select what should be output on UAVCAN ESC 5. + * Select what should be output on SIM_GZ ESC 5. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -9638,12 +9254,12 @@ PARAM_DEFINE_INT32(UAVCAN_EC_FUNC4, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC5, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC5, 0); /** - * UAVCAN ESC 6 Output Function + * SIM_GZ ESC 6 Output Function * - * Select what should be output on UAVCAN ESC 6. + * Select what should be output on SIM_GZ ESC 6. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -9702,12 +9318,12 @@ PARAM_DEFINE_INT32(UAVCAN_EC_FUNC5, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC6, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC6, 0); /** - * UAVCAN ESC 7 Output Function + * SIM_GZ ESC 7 Output Function * - * Select what should be output on UAVCAN ESC 7. + * Select what should be output on SIM_GZ ESC 7. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -9766,12 +9382,12 @@ PARAM_DEFINE_INT32(UAVCAN_EC_FUNC6, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC7, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC7, 0); /** - * UAVCAN ESC 8 Output Function + * SIM_GZ ESC 8 Output Function * - * Select what should be output on UAVCAN ESC 8. + * Select what should be output on SIM_GZ ESC 8. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -9830,316 +9446,428 @@ PARAM_DEFINE_INT32(UAVCAN_EC_FUNC7, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC8, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC8, 0); /** - * UAVCAN ESC 1 Minimum Value + * SIM_GZ ESC 1 Disarmed Value + * + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS1, 0); + +/** + * SIM_GZ ESC 2 Disarmed Value + * + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS2, 0); + +/** + * SIM_GZ ESC 3 Disarmed Value + * + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS3, 0); + +/** + * SIM_GZ ESC 4 Disarmed Value + * + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS4, 0); + +/** + * SIM_GZ ESC 5 Disarmed Value + * + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS5, 0); + +/** + * SIM_GZ ESC 6 Disarmed Value + * + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS6, 0); + +/** + * SIM_GZ ESC 7 Disarmed Value + * + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS7, 0); + +/** + * SIM_GZ ESC 8 Disarmed Value + * + * This is the output value that is set when not armed. + * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * + * + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS8, 0); + +/** + * SIM_GZ ESC 1 Minimum Value * * Minimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN1, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN1, 0); /** - * UAVCAN ESC 2 Minimum Value + * SIM_GZ ESC 2 Minimum Value * * Minimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN2, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN2, 0); /** - * UAVCAN ESC 3 Minimum Value + * SIM_GZ ESC 3 Minimum Value * * Minimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN3, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN3, 0); /** - * UAVCAN ESC 4 Minimum Value + * SIM_GZ ESC 4 Minimum Value * * Minimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN4, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN4, 0); /** - * UAVCAN ESC 5 Minimum Value + * SIM_GZ ESC 5 Minimum Value * * Minimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN5, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN5, 0); /** - * UAVCAN ESC 6 Minimum Value + * SIM_GZ ESC 6 Minimum Value * * Minimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN6, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN6, 0); /** - * UAVCAN ESC 7 Minimum Value + * SIM_GZ ESC 7 Minimum Value * * Minimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN7, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN7, 0); /** - * UAVCAN ESC 8 Minimum Value + * SIM_GZ ESC 8 Minimum Value * * Minimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN8, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN8, 0); /** - * UAVCAN ESC 1 Maximum Value + * SIM_GZ ESC 1 Maximum Value * * Maxmimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX1, 8191); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX1, 1000); /** - * UAVCAN ESC 2 Maximum Value + * SIM_GZ ESC 2 Maximum Value * * Maxmimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX2, 8191); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX2, 1000); /** - * UAVCAN ESC 3 Maximum Value + * SIM_GZ ESC 3 Maximum Value * * Maxmimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX3, 8191); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX3, 1000); /** - * UAVCAN ESC 4 Maximum Value + * SIM_GZ ESC 4 Maximum Value * * Maxmimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX4, 8191); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX4, 1000); /** - * UAVCAN ESC 5 Maximum Value + * SIM_GZ ESC 5 Maximum Value * * Maxmimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX5, 8191); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX5, 1000); /** - * UAVCAN ESC 6 Maximum Value + * SIM_GZ ESC 6 Maximum Value * * Maxmimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX6, 8191); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX6, 1000); /** - * UAVCAN ESC 7 Maximum Value + * SIM_GZ ESC 7 Maximum Value * * Maxmimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX7, 8191); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX7, 1000); /** - * UAVCAN ESC 8 Maximum Value + * SIM_GZ ESC 8 Maximum Value * * Maxmimum output value (when not disarmed). * * * @group Actuator Outputs * @min 0 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX8, 8191); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX8, 1000); /** - * UAVCAN ESC 1 Failsafe Value + * SIM_GZ ESC 1 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC1). + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC1). * * * @group Actuator Outputs * @min -1 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL1, -1); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL1, -1); /** - * UAVCAN ESC 2 Failsafe Value + * SIM_GZ ESC 2 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC2). + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC2). * * * @group Actuator Outputs * @min -1 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL2, -1); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL2, -1); /** - * UAVCAN ESC 3 Failsafe Value + * SIM_GZ ESC 3 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC3). + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC3). * * * @group Actuator Outputs * @min -1 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL3, -1); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL3, -1); /** - * UAVCAN ESC 4 Failsafe Value + * SIM_GZ ESC 4 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC4). + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC4). * * * @group Actuator Outputs * @min -1 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL4, -1); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL4, -1); /** - * UAVCAN ESC 5 Failsafe Value + * SIM_GZ ESC 5 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC5). + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC5). * * * @group Actuator Outputs * @min -1 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL5, -1); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL5, -1); /** - * UAVCAN ESC 6 Failsafe Value + * SIM_GZ ESC 6 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC6). + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC6). * * * @group Actuator Outputs * @min -1 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL6, -1); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL6, -1); /** - * UAVCAN ESC 7 Failsafe Value + * SIM_GZ ESC 7 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC7). + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC7). * * * @group Actuator Outputs * @min -1 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL7, -1); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL7, -1); /** - * UAVCAN ESC 8 Failsafe Value + * SIM_GZ ESC 8 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC8). + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC8). * * * @group Actuator Outputs * @min -1 - * @max 8191 + * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL8, -1); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL8, -1); /** - * UAVCAN Servo 1 Output Function + * SIM_GZ Servo 1 Output Function * - * Select what should be output on UAVCAN Servo 1. + * Select what should be output on SIM_GZ Servo 1. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -10198,12 +9926,12 @@ PARAM_DEFINE_INT32(UAVCAN_EC_FAIL8, -1); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC1, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC1, 0); /** - * UAVCAN Servo 2 Output Function + * SIM_GZ Servo 2 Output Function * - * Select what should be output on UAVCAN Servo 2. + * Select what should be output on SIM_GZ Servo 2. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -10262,12 +9990,12 @@ PARAM_DEFINE_INT32(UAVCAN_SV_FUNC1, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC2, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC2, 0); /** - * UAVCAN Servo 3 Output Function + * SIM_GZ Servo 3 Output Function * - * Select what should be output on UAVCAN Servo 3. + * Select what should be output on SIM_GZ Servo 3. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -10326,12 +10054,12 @@ PARAM_DEFINE_INT32(UAVCAN_SV_FUNC2, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC3, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC3, 0); /** - * UAVCAN Servo 4 Output Function + * SIM_GZ Servo 4 Output Function * - * Select what should be output on UAVCAN Servo 4. + * Select what should be output on SIM_GZ Servo 4. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -10390,12 +10118,12 @@ PARAM_DEFINE_INT32(UAVCAN_SV_FUNC3, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC4, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC4, 0); /** - * UAVCAN Servo 5 Output Function + * SIM_GZ Servo 5 Output Function * - * Select what should be output on UAVCAN Servo 5. + * Select what should be output on SIM_GZ Servo 5. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -10454,12 +10182,12 @@ PARAM_DEFINE_INT32(UAVCAN_SV_FUNC4, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC5, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC5, 0); /** - * UAVCAN Servo 6 Output Function + * SIM_GZ Servo 6 Output Function * - * Select what should be output on UAVCAN Servo 6. + * Select what should be output on SIM_GZ Servo 6. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -10518,12 +10246,12 @@ PARAM_DEFINE_INT32(UAVCAN_SV_FUNC5, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC6, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC6, 0); /** - * UAVCAN Servo 7 Output Function + * SIM_GZ Servo 7 Output Function * - * Select what should be output on UAVCAN Servo 7. + * Select what should be output on SIM_GZ Servo 7. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -10582,12 +10310,12 @@ PARAM_DEFINE_INT32(UAVCAN_SV_FUNC6, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC7, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC7, 0); /** - * UAVCAN Servo 8 Output Function + * SIM_GZ Servo 8 Output Function * - * Select what should be output on UAVCAN Servo 8. + * Select what should be output on SIM_GZ Servo 8. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -10646,10 +10374,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_FUNC7, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC8, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC8, 0); /** - * UAVCAN Servo 1 Disarmed Value + * SIM_GZ Servo 1 Disarmed Value * * This is the output value that is set when not armed. * @@ -10660,10 +10388,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_FUNC8, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS1, 500); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS1, 500); /** - * UAVCAN Servo 2 Disarmed Value + * SIM_GZ Servo 2 Disarmed Value * * This is the output value that is set when not armed. * @@ -10674,10 +10402,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_DIS1, 500); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS2, 500); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS2, 500); /** - * UAVCAN Servo 3 Disarmed Value + * SIM_GZ Servo 3 Disarmed Value * * This is the output value that is set when not armed. * @@ -10688,10 +10416,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_DIS2, 500); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS3, 500); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS3, 500); /** - * UAVCAN Servo 4 Disarmed Value + * SIM_GZ Servo 4 Disarmed Value * * This is the output value that is set when not armed. * @@ -10702,10 +10430,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_DIS3, 500); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS4, 500); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS4, 500); /** - * UAVCAN Servo 5 Disarmed Value + * SIM_GZ Servo 5 Disarmed Value * * This is the output value that is set when not armed. * @@ -10716,10 +10444,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_DIS4, 500); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS5, 500); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS5, 500); /** - * UAVCAN Servo 6 Disarmed Value + * SIM_GZ Servo 6 Disarmed Value * * This is the output value that is set when not armed. * @@ -10730,10 +10458,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_DIS5, 500); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS6, 500); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS6, 500); /** - * UAVCAN Servo 7 Disarmed Value + * SIM_GZ Servo 7 Disarmed Value * * This is the output value that is set when not armed. * @@ -10744,10 +10472,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_DIS6, 500); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS7, 500); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS7, 500); /** - * UAVCAN Servo 8 Disarmed Value + * SIM_GZ Servo 8 Disarmed Value * * This is the output value that is set when not armed. * @@ -10758,10 +10486,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_DIS7, 500); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS8, 500); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS8, 500); /** - * UAVCAN Servo 1 Minimum Value + * SIM_GZ Servo 1 Minimum Value * * Minimum output value (when not disarmed). * @@ -10770,10 +10498,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_DIS8, 500); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN1, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN1, 0); /** - * UAVCAN Servo 2 Minimum Value + * SIM_GZ Servo 2 Minimum Value * * Minimum output value (when not disarmed). * @@ -10782,10 +10510,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MIN1, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN2, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN2, 0); /** - * UAVCAN Servo 3 Minimum Value + * SIM_GZ Servo 3 Minimum Value * * Minimum output value (when not disarmed). * @@ -10794,10 +10522,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MIN2, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN3, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN3, 0); /** - * UAVCAN Servo 4 Minimum Value + * SIM_GZ Servo 4 Minimum Value * * Minimum output value (when not disarmed). * @@ -10806,10 +10534,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MIN3, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN4, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN4, 0); /** - * UAVCAN Servo 5 Minimum Value + * SIM_GZ Servo 5 Minimum Value * * Minimum output value (when not disarmed). * @@ -10818,10 +10546,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MIN4, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN5, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN5, 0); /** - * UAVCAN Servo 6 Minimum Value + * SIM_GZ Servo 6 Minimum Value * * Minimum output value (when not disarmed). * @@ -10830,10 +10558,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MIN5, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN6, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN6, 0); /** - * UAVCAN Servo 7 Minimum Value + * SIM_GZ Servo 7 Minimum Value * * Minimum output value (when not disarmed). * @@ -10842,10 +10570,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MIN6, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN7, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN7, 0); /** - * UAVCAN Servo 8 Minimum Value + * SIM_GZ Servo 8 Minimum Value * * Minimum output value (when not disarmed). * @@ -10854,10 +10582,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MIN7, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN8, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN8, 0); /** - * UAVCAN Servo 1 Maximum Value + * SIM_GZ Servo 1 Maximum Value * * Maxmimum output value (when not disarmed). * @@ -10866,10 +10594,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MIN8, 0); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX1, 1000); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX1, 1000); /** - * UAVCAN Servo 2 Maximum Value + * SIM_GZ Servo 2 Maximum Value * * Maxmimum output value (when not disarmed). * @@ -10878,10 +10606,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MAX1, 1000); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX2, 1000); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX2, 1000); /** - * UAVCAN Servo 3 Maximum Value + * SIM_GZ Servo 3 Maximum Value * * Maxmimum output value (when not disarmed). * @@ -10890,10 +10618,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MAX2, 1000); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX3, 1000); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX3, 1000); /** - * UAVCAN Servo 4 Maximum Value + * SIM_GZ Servo 4 Maximum Value * * Maxmimum output value (when not disarmed). * @@ -10902,10 +10630,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MAX3, 1000); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX4, 1000); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX4, 1000); /** - * UAVCAN Servo 5 Maximum Value + * SIM_GZ Servo 5 Maximum Value * * Maxmimum output value (when not disarmed). * @@ -10914,10 +10642,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MAX4, 1000); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX5, 1000); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX5, 1000); /** - * UAVCAN Servo 6 Maximum Value + * SIM_GZ Servo 6 Maximum Value * * Maxmimum output value (when not disarmed). * @@ -10926,10 +10654,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MAX5, 1000); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX6, 1000); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX6, 1000); /** - * UAVCAN Servo 7 Maximum Value + * SIM_GZ Servo 7 Maximum Value * * Maxmimum output value (when not disarmed). * @@ -10938,10 +10666,10 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MAX6, 1000); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX7, 1000); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX7, 1000); /** - * UAVCAN Servo 8 Maximum Value + * SIM_GZ Servo 8 Maximum Value * * Maxmimum output value (when not disarmed). * @@ -10950,166 +10678,166 @@ PARAM_DEFINE_INT32(UAVCAN_SV_MAX7, 1000); * @min 0 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX8, 1000); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX8, 1000); /** - * UAVCAN Servo 1 Failsafe Value + * SIM_GZ Servo 1 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC1). + * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC1). * * * @group Actuator Outputs * @min -1 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL1, -1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL1, -1); /** - * UAVCAN Servo 2 Failsafe Value + * SIM_GZ Servo 2 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC2). + * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC2). * * * @group Actuator Outputs * @min -1 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL2, -1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL2, -1); /** - * UAVCAN Servo 3 Failsafe Value + * SIM_GZ Servo 3 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC3). + * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC3). * * * @group Actuator Outputs * @min -1 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL3, -1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL3, -1); /** - * UAVCAN Servo 4 Failsafe Value + * SIM_GZ Servo 4 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC4). + * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC4). * * * @group Actuator Outputs * @min -1 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL4, -1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL4, -1); /** - * UAVCAN Servo 5 Failsafe Value + * SIM_GZ Servo 5 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC5). + * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC5). * * * @group Actuator Outputs * @min -1 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL5, -1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL5, -1); /** - * UAVCAN Servo 6 Failsafe Value + * SIM_GZ Servo 6 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC6). + * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC6). * * * @group Actuator Outputs * @min -1 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL6, -1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL6, -1); /** - * UAVCAN Servo 7 Failsafe Value + * SIM_GZ Servo 7 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC7). + * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC7). * * * @group Actuator Outputs * @min -1 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL7, -1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL7, -1); /** - * UAVCAN Servo 8 Failsafe Value + * SIM_GZ Servo 8 Failsafe Value * * This is the output value that is set when in failsafe mode. * - * When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC8). + * When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC8). * * * @group Actuator Outputs * @min -1 * @max 1000 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL8, -1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL8, -1); /** - * Reverse Output Range for UAVCAN + * Reverse Output Range for SIM_GZ * * Allows to reverse the output range for each channel. * Note: this is only useful for servos. * * * @group Actuator Outputs - * @bit 0 UAVCAN ESC 1 - * @bit 1 UAVCAN ESC 2 - * @bit 2 UAVCAN ESC 3 - * @bit 3 UAVCAN ESC 4 - * @bit 4 UAVCAN ESC 5 - * @bit 5 UAVCAN ESC 6 - * @bit 6 UAVCAN ESC 7 - * @bit 7 UAVCAN ESC 8 + * @bit 0 SIM_GZ ESC 1 + * @bit 1 SIM_GZ ESC 2 + * @bit 2 SIM_GZ ESC 3 + * @bit 3 SIM_GZ ESC 4 + * @bit 4 SIM_GZ ESC 5 + * @bit 5 SIM_GZ ESC 6 + * @bit 6 SIM_GZ ESC 7 + * @bit 7 SIM_GZ ESC 8 * @min 0 * @max 255 */ -PARAM_DEFINE_INT32(UAVCAN_EC_REV, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_REV, 0); /** - * Reverse Output Range for UAVCAN + * Reverse Output Range for SIM_GZ * * Allows to reverse the output range for each channel. * Note: this is only useful for servos. * * * @group Actuator Outputs - * @bit 0 UAVCAN Servo 1 - * @bit 1 UAVCAN Servo 2 - * @bit 2 UAVCAN Servo 3 - * @bit 3 UAVCAN Servo 4 - * @bit 4 UAVCAN Servo 5 - * @bit 5 UAVCAN Servo 6 - * @bit 6 UAVCAN Servo 7 - * @bit 7 UAVCAN Servo 8 + * @bit 0 SIM_GZ Servo 1 + * @bit 1 SIM_GZ Servo 2 + * @bit 2 SIM_GZ Servo 3 + * @bit 3 SIM_GZ Servo 4 + * @bit 4 SIM_GZ Servo 5 + * @bit 5 SIM_GZ Servo 6 + * @bit 6 SIM_GZ Servo 7 + * @bit 7 SIM_GZ Servo 8 * @min 0 * @max 255 */ -PARAM_DEFINE_INT32(UAVCAN_SV_REV, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_REV, 0); /** - * SIM Channel 1 Output Function + * HIL Channel 1 Output Function * - * Select what should be output on SIM Channel 1. + * Select what should be output on HIL Channel 1. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11168,12 +10896,12 @@ PARAM_DEFINE_INT32(UAVCAN_SV_REV, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC1, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC1, 0); /** - * SIM Channel 2 Output Function + * HIL Channel 2 Output Function * - * Select what should be output on SIM Channel 2. + * Select what should be output on HIL Channel 2. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11232,12 +10960,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC1, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC2, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC2, 0); /** - * SIM Channel 3 Output Function + * HIL Channel 3 Output Function * - * Select what should be output on SIM Channel 3. + * Select what should be output on HIL Channel 3. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11296,12 +11024,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC2, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC3, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC3, 0); /** - * SIM Channel 4 Output Function + * HIL Channel 4 Output Function * - * Select what should be output on SIM Channel 4. + * Select what should be output on HIL Channel 4. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11360,12 +11088,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC3, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC4, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC4, 0); /** - * SIM Channel 5 Output Function + * HIL Channel 5 Output Function * - * Select what should be output on SIM Channel 5. + * Select what should be output on HIL Channel 5. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11424,12 +11152,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC4, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC5, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC5, 0); /** - * SIM Channel 6 Output Function + * HIL Channel 6 Output Function * - * Select what should be output on SIM Channel 6. + * Select what should be output on HIL Channel 6. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11488,12 +11216,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC5, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC6, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC6, 0); /** - * SIM Channel 7 Output Function + * HIL Channel 7 Output Function * - * Select what should be output on SIM Channel 7. + * Select what should be output on HIL Channel 7. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11552,12 +11280,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC6, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC7, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC7, 0); /** - * SIM Channel 8 Output Function + * HIL Channel 8 Output Function * - * Select what should be output on SIM Channel 8. + * Select what should be output on HIL Channel 8. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11616,12 +11344,140 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC7, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC8, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC8, 0); /** - * SIM Channel 9 Output Function + * HIL Channel 9 Output Function * - * Select what should be output on SIM Channel 9. + * Select what should be output on HIL Channel 9. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * + * + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel + */ +PARAM_DEFINE_INT32(HIL_ACT_FUNC9, 0); + +/** + * HIL Channel 10 Output Function + * + * Select what should be output on HIL Channel 10. + * + * The default failsafe value is set according to the selected function: + * - 'Min' for ConstantMin + * - 'Max' for ConstantMax + * - 'Max' for Parachute + * - ('Max'+'Min')/2 for Servos + * - 'Disarmed' for the rest + * + * + * @group Actuator Outputs + * @value 0 Disabled + * @value 1 Constant Min + * @value 2 Constant Max + * @value 101 Motor 1 + * @value 102 Motor 2 + * @value 103 Motor 3 + * @value 104 Motor 4 + * @value 105 Motor 5 + * @value 106 Motor 6 + * @value 107 Motor 7 + * @value 108 Motor 8 + * @value 109 Motor 9 + * @value 110 Motor 10 + * @value 111 Motor 11 + * @value 112 Motor 12 + * @value 201 Servo 1 + * @value 202 Servo 2 + * @value 203 Servo 3 + * @value 204 Servo 4 + * @value 205 Servo 5 + * @value 206 Servo 6 + * @value 207 Servo 7 + * @value 208 Servo 8 + * @value 301 Offboard Actuator Set 1 + * @value 302 Offboard Actuator Set 2 + * @value 303 Offboard Actuator Set 3 + * @value 304 Offboard Actuator Set 4 + * @value 305 Offboard Actuator Set 5 + * @value 306 Offboard Actuator Set 6 + * @value 400 Landing Gear + * @value 401 Parachute + * @value 402 RC Roll + * @value 403 RC Pitch + * @value 404 RC Throttle + * @value 405 RC Yaw + * @value 406 RC Flaps + * @value 407 RC AUX 1 + * @value 408 RC AUX 2 + * @value 409 RC AUX 3 + * @value 410 RC AUX 4 + * @value 411 RC AUX 5 + * @value 412 RC AUX 6 + * @value 420 Gimbal Roll + * @value 421 Gimbal Pitch + * @value 422 Gimbal Yaw + * @value 430 Gripper + * @value 440 Landing Gear Wheel + */ +PARAM_DEFINE_INT32(HIL_ACT_FUNC10, 0); + +/** + * HIL Channel 11 Output Function + * + * Select what should be output on HIL Channel 11. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11680,12 +11536,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC8, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC9, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC11, 0); /** - * SIM Channel 10 Output Function + * HIL Channel 12 Output Function * - * Select what should be output on SIM Channel 10. + * Select what should be output on HIL Channel 12. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11744,12 +11600,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC9, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC10, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC12, 0); /** - * SIM Channel 11 Output Function + * HIL Channel 13 Output Function * - * Select what should be output on SIM Channel 11. + * Select what should be output on HIL Channel 13. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11808,12 +11664,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC10, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC11, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC13, 0); /** - * SIM Channel 12 Output Function + * HIL Channel 14 Output Function * - * Select what should be output on SIM Channel 12. + * Select what should be output on HIL Channel 14. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11872,12 +11728,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC11, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC12, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC14, 0); /** - * SIM Channel 13 Output Function + * HIL Channel 15 Output Function * - * Select what should be output on SIM Channel 13. + * Select what should be output on HIL Channel 15. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -11936,12 +11792,12 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC12, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC13, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC15, 0); /** - * SIM Channel 14 Output Function + * HIL Channel 16 Output Function * - * Select what should be output on SIM Channel 14. + * Select what should be output on HIL Channel 16. * * The default failsafe value is set according to the selected function: * - 'Min' for ConstantMin @@ -12000,225 +11856,369 @@ PARAM_DEFINE_INT32(PWM_MAIN_FUNC13, 0); * @value 430 Gripper * @value 440 Landing Gear Wheel */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC14, 0); +PARAM_DEFINE_INT32(HIL_ACT_FUNC16, 0); + +/** + * Reverse Output Range for HIL + * + * Allows to reverse the output range for each channel. + * Note: this is only useful for servos. + * + * + * @group Actuator Outputs + * @bit 0 HIL Channel 1 + * @bit 1 HIL Channel 2 + * @bit 2 HIL Channel 3 + * @bit 3 HIL Channel 4 + * @bit 4 HIL Channel 5 + * @bit 5 HIL Channel 6 + * @bit 6 HIL Channel 7 + * @bit 7 HIL Channel 8 + * @bit 8 HIL Channel 9 + * @bit 9 HIL Channel 10 + * @bit 10 HIL Channel 11 + * @bit 11 HIL Channel 12 + * @bit 12 HIL Channel 13 + * @bit 13 HIL Channel 14 + * @bit 14 HIL Channel 15 + * @bit 15 HIL Channel 16 + * @min 0 + * @max 65535 + */ +PARAM_DEFINE_INT32(HIL_ACT_REV, 0); + +/** + * MAVLink Config for instance 0 + * + * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance + * + * + * @group MAVLink + * @value 0 Disabled + * @value 1 Uart1 + * @value 2 Uart2 + * @value 3 Uart3 + * @value 4 Uart4 + * @value 5 Uart5 + * @value 6 Uart6 + * @value 7 Uart7 + * @value 8 Uart8 + * @value 20 UBS1 + * @value 21 USB2 + * @value 30 UDP + * @value 31 TCP + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_0_CONFIG, 0); + +/** + * MAVLink Config for instance 1 + * + * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance + * + * + * @group MAVLink + * @value 0 Disabled + * @value 1 Uart1 + * @value 2 Uart2 + * @value 3 Uart3 + * @value 4 Uart4 + * @value 5 Uart5 + * @value 6 Uart6 + * @value 7 Uart7 + * @value 8 Uart8 + * @value 20 UBS1 + * @value 21 USB2 + * @value 30 UDP + * @value 31 TCP + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_1_CONFIG, 0); + +/** + * MAVLink Config for instance 2 + * + * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance + * + * + * @group MAVLink + * @value 0 Disabled + * @value 1 Uart1 + * @value 2 Uart2 + * @value 3 Uart3 + * @value 4 Uart4 + * @value 5 Uart5 + * @value 6 Uart6 + * @value 7 Uart7 + * @value 8 Uart8 + * @value 20 UBS1 + * @value 21 USB2 + * @value 30 UDP + * @value 31 TCP + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_2_CONFIG, 0); + +/** + * MAVLink Mode for instance 0 + * + * The MAVLink Mode defines the set of streamed messages (for example the + * vehicle's attitude) and their sending rates. + * + * + * @group MAVLink + * @value 0 Normal + * @value 1 Custom + * @value 2 Onboard + * @value 3 OSD + * @value 4 Magic + * @value 5 Config + * @value 7 Minimal + * @value 8 External Vision + * @value 10 Gimbal + * @value 11 Onboard Low Bandwidth + * @value 12 uAvionix + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_0_MODE, 0); + +/** + * MAVLink Mode for instance 1 + * + * The MAVLink Mode defines the set of streamed messages (for example the + * vehicle's attitude) and their sending rates. + * + * + * @group MAVLink + * @value 0 Normal + * @value 1 Custom + * @value 2 Onboard + * @value 3 OSD + * @value 4 Magic + * @value 5 Config + * @value 7 Minimal + * @value 8 External Vision + * @value 10 Gimbal + * @value 11 Onboard Low Bandwidth + * @value 12 uAvionix + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_1_MODE, 2); + +/** + * MAVLink Mode for instance 2 + * + * The MAVLink Mode defines the set of streamed messages (for example the + * vehicle's attitude) and their sending rates. + * + * + * @group MAVLink + * @value 0 Normal + * @value 1 Custom + * @value 2 Onboard + * @value 3 OSD + * @value 4 Magic + * @value 5 Config + * @value 7 Minimal + * @value 8 External Vision + * @value 10 Gimbal + * @value 11 Onboard Low Bandwidth + * @value 12 uAvionix + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_2_MODE, 0); + +/** + * Maximum MAVLink sending rate for instance 0 + * + * Configure the maximum sending rate for the MAVLink streams in Bytes/sec. + * If the configured streams exceed the maximum rate, the sending rate of + * each stream is automatically decreased. + * + * If this is set to 0 a value of half of the theoretical maximum bandwidth is used. + * This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on + * 8N1-configured links). + * + * + * @group MAVLink + * @min 0 + * @unit B/s + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_0_RATE, 1200); + +/** + * Maximum MAVLink sending rate for instance 1 + * + * Configure the maximum sending rate for the MAVLink streams in Bytes/sec. + * If the configured streams exceed the maximum rate, the sending rate of + * each stream is automatically decreased. + * + * If this is set to 0 a value of half of the theoretical maximum bandwidth is used. + * This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on + * 8N1-configured links). + * + * + * @group MAVLink + * @min 0 + * @unit B/s + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_1_RATE, 0); + +/** + * Maximum MAVLink sending rate for instance 2 + * + * Configure the maximum sending rate for the MAVLink streams in Bytes/sec. + * If the configured streams exceed the maximum rate, the sending rate of + * each stream is automatically decreased. + * + * If this is set to 0 a value of half of the theoretical maximum bandwidth is used. + * This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on + * 8N1-configured links). + * + * + * @group MAVLink + * @min 0 + * @unit B/s + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_2_RATE, 0); /** - * SIM Channel 15 Output Function + * Enable MAVLink Message forwarding for instance 0 * - * Select what should be output on SIM Channel 15. + * If enabled, forward incoming MAVLink messages to other MAVLink ports if the + * message is either broadcast or the target is not the autopilot. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * This allows for example a GCS to talk to a camera that is connected to the + * autopilot via MAVLink (on a different link than the GCS). * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group MAVLink + * @boolean + * @reboot_required True */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC15, 0); +PARAM_DEFINE_INT32(MAV_0_FORWARD, 1); /** - * SIM Channel 16 Output Function + * Enable MAVLink Message forwarding for instance 1 * - * Select what should be output on SIM Channel 16. + * If enabled, forward incoming MAVLink messages to other MAVLink ports if the + * message is either broadcast or the target is not the autopilot. * - * The default failsafe value is set according to the selected function: - * - 'Min' for ConstantMin - * - 'Max' for ConstantMax - * - 'Max' for Parachute - * - ('Max'+'Min')/2 for Servos - * - 'Disarmed' for the rest + * This allows for example a GCS to talk to a camera that is connected to the + * autopilot via MAVLink (on a different link than the GCS). * * - * @group Actuator Outputs - * @value 0 Disabled - * @value 1 Constant Min - * @value 2 Constant Max - * @value 101 Motor 1 - * @value 102 Motor 2 - * @value 103 Motor 3 - * @value 104 Motor 4 - * @value 105 Motor 5 - * @value 106 Motor 6 - * @value 107 Motor 7 - * @value 108 Motor 8 - * @value 109 Motor 9 - * @value 110 Motor 10 - * @value 111 Motor 11 - * @value 112 Motor 12 - * @value 201 Servo 1 - * @value 202 Servo 2 - * @value 203 Servo 3 - * @value 204 Servo 4 - * @value 205 Servo 5 - * @value 206 Servo 6 - * @value 207 Servo 7 - * @value 208 Servo 8 - * @value 301 Offboard Actuator Set 1 - * @value 302 Offboard Actuator Set 2 - * @value 303 Offboard Actuator Set 3 - * @value 304 Offboard Actuator Set 4 - * @value 305 Offboard Actuator Set 5 - * @value 306 Offboard Actuator Set 6 - * @value 400 Landing Gear - * @value 401 Parachute - * @value 402 RC Roll - * @value 403 RC Pitch - * @value 404 RC Throttle - * @value 405 RC Yaw - * @value 406 RC Flaps - * @value 407 RC AUX 1 - * @value 408 RC AUX 2 - * @value 409 RC AUX 3 - * @value 410 RC AUX 4 - * @value 411 RC AUX 5 - * @value 412 RC AUX 6 - * @value 420 Gimbal Roll - * @value 421 Gimbal Pitch - * @value 422 Gimbal Yaw - * @value 430 Gripper - * @value 440 Landing Gear Wheel + * @group MAVLink + * @boolean + * @reboot_required True */ -PARAM_DEFINE_INT32(PWM_MAIN_FUNC16, 0); +PARAM_DEFINE_INT32(MAV_1_FORWARD, 0); /** - * Reverse Output Range for SIM + * Enable MAVLink Message forwarding for instance 2 * - * Allows to reverse the output range for each channel. - * Note: this is only useful for servos. + * If enabled, forward incoming MAVLink messages to other MAVLink ports if the + * message is either broadcast or the target is not the autopilot. + * + * This allows for example a GCS to talk to a camera that is connected to the + * autopilot via MAVLink (on a different link than the GCS). * * - * @group Actuator Outputs - * @bit 0 SIM Channel 1 - * @bit 1 SIM Channel 2 - * @bit 2 SIM Channel 3 - * @bit 3 SIM Channel 4 - * @bit 4 SIM Channel 5 - * @bit 5 SIM Channel 6 - * @bit 6 SIM Channel 7 - * @bit 7 SIM Channel 8 - * @bit 8 SIM Channel 9 - * @bit 9 SIM Channel 10 - * @bit 10 SIM Channel 11 - * @bit 11 SIM Channel 12 - * @bit 12 SIM Channel 13 - * @bit 13 SIM Channel 14 - * @bit 14 SIM Channel 15 - * @bit 15 SIM Channel 16 - * @min 0 - * @max 65535 + * @group MAVLink + * @boolean + * @reboot_required True */ -PARAM_DEFINE_INT32(PWM_MAIN_REV, 0); +PARAM_DEFINE_INT32(MAV_2_FORWARD, 0); /** - * uXRCE-DDS domain ID + * Enable software throttling of mavlink on instance 0 * - * uXRCE-DDS domain ID + * If enabled, MAVLink messages will be throttled according to + * `txbuf` field reported by radio_status. + * + * Requires a radio to send the mavlink message RADIO_STATUS. + * * - * @group UXRCE-DDS Client - * @category System + * @group MAVLink + * @boolean * @reboot_required True */ -PARAM_DEFINE_INT32(UXRCE_DDS_DOM_ID, 0); +PARAM_DEFINE_INT32(MAV_0_RADIO_CTL, 1); /** - * uXRCE-DDS Session key + * Enable software throttling of mavlink on instance 1 * - * uXRCE-DDS key, must be different from zero. - * In a single agent - multi client configuration, each client - * must have a unique session key. + * If enabled, MAVLink messages will be throttled according to + * `txbuf` field reported by radio_status. + * + * Requires a radio to send the mavlink message RADIO_STATUS. * * - * @group UXRCE-DDS Client - * @category System + * @group MAVLink + * @boolean * @reboot_required True */ -PARAM_DEFINE_INT32(UXRCE_DDS_KEY, 1); +PARAM_DEFINE_INT32(MAV_1_RADIO_CTL, 1); /** - * Enable Gripper actuation in Payload Deliverer + * Enable software throttling of mavlink on instance 2 * + * If enabled, MAVLink messages will be throttled according to + * `txbuf` field reported by radio_status. + * + * Requires a radio to send the mavlink message RADIO_STATUS. * * - * @group Payload Deliverer + * @group MAVLink * @boolean * @reboot_required True */ -PARAM_DEFINE_INT32(PD_GRIPPER_EN, 0); +PARAM_DEFINE_INT32(MAV_2_RADIO_CTL, 1); /** - * Type of Gripper (Servo, etc.) + * Enable serial flow control for instance 0 * + * This is used to force flow control on or off for the the mavlink + * instance. By default it is auto detected. Use when auto detection fails. * * - * @group Payload Deliverer - * @value -1 Undefined - * @value 0 Servo - * @min -1 - * @max 0 + * @group MAVLink + * @value 0 Force off + * @value 1 Force on + * @value 2 Auto-detected + * @reboot_required True */ -PARAM_DEFINE_INT32(PD_GRIPPER_TYPE, 0); +PARAM_DEFINE_INT32(MAV_0_FLOW_CTRL, 2); /** - * Timeout for successful gripper actuation acknowledgement + * Enable serial flow control for instance 1 * - * Maximum time Gripper will wait while the successful griper actuation isn't recognised. - * If the gripper has no feedback sensor, it will simply wait for - * this time before considering gripper actuation successful and publish a - * 'VehicleCommandAck' signaling successful gripper action + * This is used to force flow control on or off for the the mavlink + * instance. By default it is auto detected. Use when auto detection fails. * * - * @group Payload Deliverer - * @min 0 - * @unit s + * @group MAVLink + * @value 0 Force off + * @value 1 Force on + * @value 2 Auto-detected + * @reboot_required True */ -PARAM_DEFINE_FLOAT(PD_GRIPPER_TO, 3); +PARAM_DEFINE_INT32(MAV_1_FLOW_CTRL, 2); + +/** + * Enable serial flow control for instance 2 + * + * This is used to force flow control on or off for the the mavlink + * instance. By default it is auto detected. Use when auto detection fails. + * + * + * @group MAVLink + * @value 0 Force off + * @value 1 Force on + * @value 2 Auto-detected + * @reboot_required True + */ +PARAM_DEFINE_INT32(MAV_2_FLOW_CTRL, 2);