From f09c9ebb259369c58dd4d0f20314b8e383437e0f Mon Sep 17 00:00:00 2001 From: latercomer Date: Sat, 28 Sep 2024 09:49:27 +0800 Subject: [PATCH] =?UTF-8?q?=E8=B0=83=E6=95=B4=E4=BA=86docs=E7=A4=BE?= =?UTF-8?q?=E5=8C=BA=E6=94=AF=E6=8C=81=E9=83=A8=E5=88=86=E5=86=85=E5=AE=B9?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: latercomer --- docs/community/code-of-conduct.md | 229 + .../community/contribute.md | 0 docs/community/contributing.md | 1 - .../community/image/github-flow.png | Bin .../image/image-20221021163100119.png | Bin .../image/image-20221021163428794.png | Bin .../image/image-20221021163614865.png | Bin .../image/image-20221021164334189.png | Bin .../community/image/vscode-git-sign-off.png | Bin docs/community/index.md | 14 +- .../support.md" => docs/community/support.md | 8 +- .../git-basic-help.md" | 0 .../image/image-20221021165220086.png" | Bin .../image/image-20221021165804529.png" | Bin .../image/image-20221021165903669.png" | Bin .../image/image-20221021170033561.png" | Bin .../image/image-20221022090648166.png" | Bin .../image/image-20221022090821858.png" | Bin .../FMUv5_stm32_pinout.xlsx" | Bin .../README.md" | 0 .../fw-struct.png" | Bin .../sgd-hw-struct.png" | Bin .../README.md" | 0 .../README.md" | 0 .../oem718d.md" | 0 .../ub482.md" | 0 .../README.md" | 0 .../README.md" | 0 .../README.md" | 0 .../dsm.md" | 0 .../sbus-reverse.png" | Bin .../sbus.md" | 0 .../README.md" | 9 - pkgs/device/device.cpp | 94 - pkgs/device/device.hpp | 83 +- pkgs/device/i2c.cpp | 24 +- pkgs/device/i2c.hpp | 6 +- pkgs/device/rt-device.hpp | 135 + pkgs/param/interface/param_autogen.hpp | 1852 +-- pkgs/param/module_params.c | 12933 ++++++++-------- 40 files changed, 7965 insertions(+), 7423 deletions(-) create mode 100644 docs/community/code-of-conduct.md rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/contribute.md" => docs/community/contribute.md (100%) delete mode 100644 docs/community/contributing.md rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/github-flow.png" => docs/community/image/github-flow.png (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163100119.png" => docs/community/image/image-20221021163100119.png (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163428794.png" => docs/community/image/image-20221021163428794.png (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163614865.png" => docs/community/image/image-20221021163614865.png (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021164334189.png" => docs/community/image/image-20221021164334189.png (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/vscode-git-sign-off.png" => docs/community/image/vscode-git-sign-off.png (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/support.md" => docs/community/support.md (77%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/githelper.md" => "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/git-basic-help.md" (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165220086.png" => "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165220086.png" (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165804529.png" => "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165804529.png" (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165903669.png" => "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165903669.png" (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021170033561.png" => "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021170033561.png" (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221022090648166.png" => "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221022090648166.png" (100%) rename "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221022090821858.png" => "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221022090821858.png" (100%) rename "docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/FMUv5_stm32_pinout.xlsx" => "docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/FMUv5_stm32_pinout.xlsx" (100%) rename "docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/README.md" => "docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/README.md" (100%) rename "docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/fw-struct.png" => "docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/fw-struct.png" (100%) rename "docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/sgd-hw-struct.png" => "docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/sgd-hw-struct.png" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/README.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/README.md" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/README.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/README.md" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/oem718d.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/oem718d.md" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/ub482.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/ub482.md" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\275\234\345\212\250\345\231\250/README.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\275\234\345\212\250\345\231\250/README.md" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\346\225\260\346\215\256\351\223\276/README.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\346\225\260\346\215\256\351\223\276/README.md" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/README.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/README.md" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/dsm.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/dsm.md" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/sbus-reverse.png" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/sbus-reverse.png" (100%) rename "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/sbus.md" => "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/sbus.md" (100%) delete mode 100644 "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/README.md" delete mode 100644 pkgs/device/device.cpp create mode 100644 pkgs/device/rt-device.hpp diff --git a/docs/community/code-of-conduct.md b/docs/community/code-of-conduct.md new file mode 100644 index 0000000000..6b37cec085 --- /dev/null +++ b/docs/community/code-of-conduct.md @@ -0,0 +1,229 @@ +# 行为准则 + +We pledge to adhere to the [nextpilot code of conduct](https://github.com/nextpilot/nextpilot-flight-control/blob/main/.github/CODE_OF_CONDUCT.md), which aims to foster an open and welcoming environment. + +=== "简体中文" + +``` +# 贡献者公约 + +## 我们的承诺 + +身为项目成员、贡献者、负责人,我们保证参与此社区的每个人都不受骚扰,不论其年龄、体型、身体条件、民族、性征、性别认同与表现、经验水平、教育程度、社会地位、国籍、相貌、种族、宗教信仰及性取向如何。 + +我们承诺致力于建设开放、友善、多元、包容、健康的社区环境。 + +## 我们的准则 + +有助于促进本社区积极环境的行为包括但不限于: + +* 与人为善、推己及人 +* 尊重不同的主张、观点和经历 +* 积极提出、耐心接受有益批评 +* 面对过失,承担责任、认真道歉、从中学习 +* 关注社区共同诉求,而非一己私利 + +不当行为包括但不限于: + +* 发布与性有关的言论或图像,以及任何形式的献殷勤或勾引 +* 挑衅行为、侮辱或贬损的言论、人身及政治攻击 +* 公开或私下骚扰 +* 未获明确授权擅自发布他人的资料,如地址、电子邮箱等 +* 其他有理由认定为违反职业操守的不当行为 + +## 落实之义务 + +社区负责人有责任诠释何谓“妥当行为”,并据此准则,妥善公正地认定与处置不当、威胁、冒犯及有害的行为。 + +社区负责人有权利和义务删除、编辑、拒绝违背本公约的评论(comment)、提交(commit)、代码、维基(wiki)编辑、问题(issue)等贡献。如有必要,需告知采取措施之理由。 + +## 适用范围 + +此行为标准适用于本社区全部场合,以及在其他场合代表本社区的个人。 + +代表本社区的情形包括但不限于:使用官方电子邮件与社交平台、作为指定代表参与在线或线下活动。 + +## 贯彻落实 + +如遇滥用、骚扰等不当行为,请通过 nextpilot@qq.com 向纪律检查委员举报。 +纪委将迅速审议并调查全部投诉。 + +社区全体负责人有义务保密举报者信息。 + +## 指导方针 + +社区负责人将依据下列方案判断并处置违纪行为: + +### 一、督促 + +**社区影响**:用语不当、举止不符合职业道德或不受社区欢迎。 + +**处理意见**:由社区负责人予以非公开的书面警告,阐明违纪事由、解释举止如何不妥。或将要求公开道歉。 + +### 二、警告 + +**社区影响**:一起或多起事件中的违纪行为。 + +**处理意见**:警告继续违纪之后果、违纪者在特定时间内禁止与当事人往来、不得擅自与社区执法者往来,禁令涵盖社区内外、社交网络在内的一切联络。如有违反,可致封禁乃至开除。 + +### 三、封禁 + +**社区影响**:严重违纪行为,包括屡教不改。 + +**处理意见**:违纪者在特定时间内禁止与社区的任何往来或公开联络,禁止任何与当事人公开或私下往来,不得擅自与社区执法者往来。如有违反,可致开除。 + +### 四、开除 + +**社区影响**:典型违纪行为,例如屡教不改、骚扰某个人、敌对或贬低某个群体。 + +**处理意见**:无限期禁止违纪者与项目社区的一切公开往来。 + +## 来源 + +本行为标准改编自[参与者公约][homepage]2.0版,可在此查阅:[https://www.contributor-covenant.org/zh-cn/version/2/0/code_of_conduct.html][v2.0] + +指导方针借鉴自[Mozilla纪检分级][Mozilla CoC]。 + +此行为标准常见问题请洽:[https://www.contributor-covenant.org/faq][FAQ]。 +另有诸译本:[https://www.contributor-covenant.org/translations][translations]。 + +[homepage]:https://www.contributor-covenant.org +[v2.0]: https://www.contributor-covenant.org/version/2/0/code_of_conduct.html +[Mozilla CoC]: https://github.com/mozilla/diversity +[FAQ]: https://www.contributor-covenant.org/faq +[translations]: https://www.contributor-covenant.org/translations + +``` + +=== "English" + ``` + # Contributor Covenant Code of Conduct + + ## Our Pledge + + We as members, contributors, and leaders pledge to make participation in our + community a harassment-free experience for everyone, regardless of age, body + size, visible or invisible disability, ethnicity, sex characteristics, gender + identity and expression, level of experience, education, socio-economic status, + nationality, personal appearance, race, religion, or sexual identity + and orientation. + + We pledge to act and interact in ways that contribute to an open, welcoming, + diverse, inclusive, and healthy community. + + ## Our Standards + + Examples of behavior that contributes to a positive environment for our + community include: + + * Demonstrating empathy and kindness toward other people + * Being respectful of differing opinions, viewpoints, and experiences + * Giving and gracefully accepting constructive feedback + * Accepting responsibility and apologizing to those affected by our mistakes, + and learning from the experience + * Focusing on what is best not just for us as individuals, but for the + overall community + + Examples of unacceptable behavior include: + + * The use of sexualized language or imagery, and sexual attention or + advances of any kind + * Trolling, insulting or derogatory comments, and personal or political attacks + * Public or private harassment + * Publishing others' private information, such as a physical or email + address, without their explicit permission + * Other conduct which could reasonably be considered inappropriate in a + professional setting + + ## Enforcement Responsibilities + + Community leaders are responsible for clarifying and enforcing our standards of + acceptable behavior and will take appropriate and fair corrective action in + response to any behavior that they deem inappropriate, threatening, offensive, + or harmful. + + Community leaders have the right and responsibility to remove, edit, or reject + comments, commits, code, wiki edits, issues, and other contributions that are + not aligned to this Code of Conduct, and will communicate reasons for moderation + decisions when appropriate. + + ## Scope + + This Code of Conduct applies within all community spaces, and also applies when + an individual is officially representing the community in public spaces. + Examples of representing our community include using an official e-mail address, + posting via an official social media account, or acting as an appointed + representative at an online or offline event. + + ## Enforcement + + Instances of abusive, harassing, or otherwise unacceptable behavior may be + reported to the community leaders responsible for enforcement at + nextpilot@qq.com. + All complaints will be reviewed and investigated promptly and fairly. + + All community leaders are obligated to respect the privacy and security of the + reporter of any incident. + + ## Enforcement Guidelines + + Community leaders will follow these Community Impact Guidelines in determining + the consequences for any action they deem in violation of this Code of Conduct: + + ### 1. Correction + + **Community Impact**: Use of inappropriate language or other behavior deemed + unprofessional or unwelcome in the community. + + **Consequence**: A private, written warning from community leaders, providing + clarity around the nature of the violation and an explanation of why the + behavior was inappropriate. A public apology may be requested. + + ### 2. Warning + + **Community Impact**: A violation through a single incident or series + of actions. + + **Consequence**: A warning with consequences for continued behavior. No + interaction with the people involved, including unsolicited interaction with + those enforcing the Code of Conduct, for a specified period of time. This + includes avoiding interactions in community spaces as well as external channels + like social media. Violating these terms may lead to a temporary or + permanent ban. + + ### 3. Temporary Ban + + **Community Impact**: A serious violation of community standards, including + sustained inappropriate behavior. + + **Consequence**: A temporary ban from any sort of interaction or public + communication with the community for a specified period of time. No public or + private interaction with the people involved, including unsolicited interaction + with those enforcing the Code of Conduct, is allowed during this period. + Violating these terms may lead to a permanent ban. + + ### 4. Permanent Ban + + **Community Impact**: Demonstrating a pattern of violation of community + standards, including sustained inappropriate behavior, harassment of an + individual, or aggression toward or disparagement of classes of individuals. + + **Consequence**: A permanent ban from any sort of public interaction within + the community. + + ## Attribution + + This Code of Conduct is adapted from the [Contributor Covenant][homepage], + version 2.0, available at + https://www.contributor-covenant.org/version/2/0/code_of_conduct.html. + + Community Impact Guidelines were inspired by [Mozilla's code of conduct + enforcement ladder](https://github.com/mozilla/diversity). + + [homepage]: https://www.contributor-covenant.org + + For answers to common questions about this code of conduct, see the FAQ at + https://www.contributor-covenant.org/faq. Translations are available at + https://www.contributor-covenant.org/translations. + + ``` diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/contribute.md" b/docs/community/contribute.md similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/contribute.md" rename to docs/community/contribute.md diff --git a/docs/community/contributing.md b/docs/community/contributing.md deleted file mode 100644 index 6093c2da13..0000000000 --- a/docs/community/contributing.md +++ /dev/null @@ -1 +0,0 @@ -# 贡献代码 diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/github-flow.png" b/docs/community/image/github-flow.png similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/github-flow.png" rename to docs/community/image/github-flow.png diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163100119.png" b/docs/community/image/image-20221021163100119.png similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163100119.png" rename to docs/community/image/image-20221021163100119.png diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163428794.png" b/docs/community/image/image-20221021163428794.png similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163428794.png" rename to docs/community/image/image-20221021163428794.png diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163614865.png" b/docs/community/image/image-20221021163614865.png similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021163614865.png" rename to docs/community/image/image-20221021163614865.png diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021164334189.png" b/docs/community/image/image-20221021164334189.png similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021164334189.png" rename to docs/community/image/image-20221021164334189.png diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/vscode-git-sign-off.png" b/docs/community/image/vscode-git-sign-off.png similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/vscode-git-sign-off.png" rename to docs/community/image/vscode-git-sign-off.png diff --git a/docs/community/index.md b/docs/community/index.md index bd4ec7ef98..5039984d9b 100644 --- a/docs/community/index.md +++ b/docs/community/index.md @@ -1,14 +1,12 @@ # 社区支持 -代码仓库: +欢迎来到 NextPilot 开发社区!为了营造一个开放和受欢迎的开发环境,我们承诺严格遵守[NextPilot 行为准测](./code-of-conduct.md)。 -开发环境: - -交流论坛: - -问题反馈: - -提交代码: +- [技术支持](./support.md),获取帮助,故障排查,扫码加群等 +- [贡献代码](./contribute.md),包括 [代码风格]()、[提交规范]() 等 +- [完善文档](),完善帮助文档,比如用户手册、开发指南等 +- [语言翻译]() +- [开源协议](./license.md),项目基于 [BSD 3-clause license](https://opensource.org/licenses/BSD-3-Clause) 开源协议 扫码加入`NextPilot社区支持`群,我们会提供相关技术支持,全力为大家答疑解惑。 diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/support.md" b/docs/community/support.md similarity index 77% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/support.md" rename to docs/community/support.md index bc0925a119..fee6cd43cc 100644 --- "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/support.md" +++ b/docs/community/support.md @@ -2,6 +2,12 @@ 核心开发团队和社区成员活跃于以下渠道,您可以从以下方式获得帮助。 +交流论坛: + +问题反馈: + +提交代码: + ## 故障诊断 如果您不确定问题是什么,需要帮助诊断,建议按照如下步骤: @@ -15,4 +21,4 @@ 扫码加入 NextPilot 社区支持群,我们会提供相关技术支持,全力为大家答疑解惑。 -![](https://www.nextpilot.org/community/add-to-group.jpeg) +![](./add-to-group.jpeg) diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/githelper.md" "b/docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/git-basic-help.md" similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/githelper.md" rename to "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/git-basic-help.md" diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165220086.png" "b/docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165220086.png" similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165220086.png" rename to "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165220086.png" diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165804529.png" "b/docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165804529.png" similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165804529.png" rename to "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165804529.png" diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165903669.png" "b/docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165903669.png" similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021165903669.png" rename to "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021165903669.png" diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021170033561.png" "b/docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021170033561.png" similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221021170033561.png" rename to "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221021170033561.png" diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221022090648166.png" "b/docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221022090648166.png" similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221022090648166.png" rename to "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221022090648166.png" diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221022090821858.png" "b/docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221022090821858.png" similarity index 100% rename from "docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/image/image-20221022090821858.png" rename to "docs/develop/01.\345\277\253\351\200\237\345\205\245\351\227\250/\346\272\220\347\240\201\347\211\210\346\234\254\347\256\241\347\220\206/image/image-20221022090821858.png" diff --git "a/docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/FMUv5_stm32_pinout.xlsx" "b/docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/FMUv5_stm32_pinout.xlsx" similarity index 100% rename from "docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/FMUv5_stm32_pinout.xlsx" rename to "docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/FMUv5_stm32_pinout.xlsx" diff --git "a/docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/README.md" "b/docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/README.md" similarity index 100% rename from "docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/README.md" rename to "docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/README.md" diff --git "a/docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/fw-struct.png" "b/docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/fw-struct.png" similarity index 100% rename from "docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/fw-struct.png" rename to "docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/fw-struct.png" diff --git "a/docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/sgd-hw-struct.png" "b/docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/sgd-hw-struct.png" similarity index 100% rename from "docs/develop/10.\347\241\254\344\273\266\350\256\276\350\256\241/sgd-hw-struct.png" rename to "docs/develop/02.\347\241\254\344\273\266\350\256\276\350\256\241/sgd-hw-struct.png" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/README.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/README.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/README.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/README.md" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/README.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/README.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/README.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/README.md" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/oem718d.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/oem718d.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/oem718d.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/oem718d.md" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/ub482.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/ub482.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/ub482.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\274\240\346\204\237\345\231\250/\345\215\253\346\230\237\345\257\274\350\210\252/ub482.md" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\275\234\345\212\250\345\231\250/README.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\275\234\345\212\250\345\231\250/README.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\344\275\234\345\212\250\345\231\250/README.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\344\275\234\345\212\250\345\231\250/README.md" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\346\225\260\346\215\256\351\223\276/README.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\346\225\260\346\215\256\351\223\276/README.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\346\225\260\346\215\256\351\223\276/README.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\346\225\260\346\215\256\351\223\276/README.md" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/README.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/README.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/README.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/README.md" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/dsm.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/dsm.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/dsm.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/dsm.md" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/sbus-reverse.png" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/sbus-reverse.png" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/sbus-reverse.png" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/sbus-reverse.png" diff --git "a/docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/sbus.md" "b/docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/sbus.md" similarity index 100% rename from "docs/develop/05.\350\256\276\345\244\207\351\251\261\345\212\250/\351\201\245\346\216\247\345\231\250/sbus.md" rename to "docs/develop/05.\345\244\226\350\256\276\346\224\257\346\214\201/\351\201\245\346\216\247\345\231\250/sbus.md" diff --git "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/README.md" "b/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/README.md" deleted file mode 100644 index 4d67712fd1..0000000000 --- "a/docs/develop/13.\347\244\276\345\214\272\346\224\257\346\214\201/README.md" +++ /dev/null @@ -1,9 +0,0 @@ -# 社区支持 - -欢迎来到 NextPilot 开发社区!为了营造一个开放和受欢迎的开发环境,我们承诺严格遵守[NextPilot 代码准测](https://github.com/nextpilot/nextpilot-flight-control/blob/main/.github/CODE_OF_CONDUCT.md)。 - -- [技术支持](./support.md),获取帮助,故障排查,扫码加群等 -- [贡献代码](./contribute.md),包括 [代码风格]()、[提交规范]() 等 -- [完善文档](),完善帮助文档,比如用户手册、开发指南等 -- [语言翻译]() -- [开源协议](),NextPilot 项目基于 [BSD 3-clause license](https://opensource.org/licenses/BSD-3-Clause) 开源协议 diff --git a/pkgs/device/device.cpp b/pkgs/device/device.cpp deleted file mode 100644 index ea84cb9095..0000000000 --- a/pkgs/device/device.cpp +++ /dev/null @@ -1,94 +0,0 @@ -/***************************************************************** - * _ __ __ ____ _ __ __ - * / | / /___ _ __ / /_ / __ \ (_)/ /____ / /_ - * / |/ // _ \ | |/_// __// /_/ // // // __ \ / __/ - * / /| // __/_> < / /_ / ____// // // /_/ // /_ - * /_/ |_/ \___//_/|_| \__//_/ /_//_/ \____/ \__/ - * - * Copyright All Reserved © 2015-2024 NextPilot Development Team - ******************************************************************/ - -#include "device.hpp" -#include "defines.h" - -namespace nextpilot::device { - -static rt_err_t dev_init(rt_device_t dev) { - Device *obj = (Device *)dev; - return obj->init(); -} - -static rt_err_t dev_open(rt_device_t dev, rt_uint16_t oflag) { - Device *obj = (Device *)dev; - return obj->open(oflag); -} - -static rt_err_t dev_close(rt_device_t dev) { - Device *obj = (Device *)dev; - return obj->close(); -} - -static rt_ssize_t dev_read(rt_device_t dev, rt_off_t pos, void *buffer, rt_size_t size) { - Device *obj = (Device *)dev; - return obj->read(pos, buffer, size); -} - -static rt_ssize_t dev_write(rt_device_t dev, rt_off_t pos, const void *buffer, rt_size_t size) { - Device *obj = (Device *)dev; - return obj->write(pos, buffer, size); -} - -static rt_err_t dev_control(rt_device_t dev, int cmd, void *args) { - Device *obj = (Device *)dev; - return obj->control(cmd, args); -} - -#ifdef RT_USING_DEVICE_OPS -const struct rt_device_ops _dev_ops = { - .init = dev_init, - .open = dev_open, - .close = dev_close, - .read = dev_read, - .write = dev_write, - .control = dev_control, -}; -#endif // RT_USING_DEVICE_OPS - -Device::Device() : - rt_device{ - .type = RT_Device_Class_Char, - .rx_indicate = nullptr, - .tx_complete = nullptr, -#ifdef RT_USING_DEVICE_OPS - .ops = &_dev_ops, -#else - .init = dev_init, - .open = dev_open, - .close = dev_close, - .read = dev_read, - .write = dev_write, - .control = dev_control, -#endif // RT_USING_DEVICE_OPS - .fops = nullptr, - .user_data = nullptr, - } { -} - -rt_err_t Device::init() { - // 查找bus - if (_bus_name) { - _bus_device = rt_device_find(_bus_name); - } - // 注册dev - if (_dev_name) { - return register_driver(_dev_name, 0); - } - return 0; -} - -} // namespace nextpilot::device - -// int aaa() { -// Device dev; -// return 0; -// } diff --git a/pkgs/device/device.hpp b/pkgs/device/device.hpp index ad3ea984d8..93cf8bebf1 100644 --- a/pkgs/device/device.hpp +++ b/pkgs/device/device.hpp @@ -18,14 +18,21 @@ namespace nextpilot::device { -class Device : public rt_device { +class Device { public: - Device(); + // no copy, assignment, move, move assignment + Device(const Device &) = delete; + Device &operator=(const Device &) = delete; + Device(Device &&) = delete; + Device &operator=(Device &&) = delete; + + Device() = default; Device(const char *devname) : _dev_name(devname) { } + // /dev/ist8310, DRV_DEVTYPE_IST8310, DeviceBusType_SPI, 1, PH0 Device(const char *devname, uint8_t devtype, DeviceBusType bustype, uint8_t busindex, uint8_t address) : _dev_name(devname) { // 设置device_id @@ -35,7 +42,7 @@ class Device : public rt_device { set_device_address(address); } - // /dev/ist8310, 01, spi10, spi, + // /dev/ist8310, DRV_DEVTYPE_IST8310, spi10, PH0, Device(const char *devname, uint8_t devtype, const char *busname, uint8_t address) : _dev_name(devname), _bus_name(busname) { @@ -58,30 +65,14 @@ class Device : public rt_device { set_device_address(address); } - // no copy, assignment, move, move assignment - Device(const Device &) = delete; - Device &operator=(const Device &) = delete; - Device(Device &&) = delete; - Device &operator=(Device &&) = delete; - - virtual ~Device(); + virtual ~Device() = default; /** * Initialise the driver and make it ready for use. * * @return OK if the driver initialized OK, negative errno otherwise; */ - virtual rt_err_t init(); - - virtual rt_err_t open(rt_uint16_t oflag) { - return 0; - } - - virtual rt_err_t control(int cmd, void *args) { - return 0; - } - - virtual rt_err_t close() { + virtual rt_err_t init() { return 0; } @@ -134,44 +125,17 @@ class Device : public rt_device { return 0; } - virtual off_t seek(off_t offset, int whence) { - return 0; - } - + /** + * Perform a device-specific operation. + * + * @param operation The operation to perform. + * @param arg An argument to the operation. + * @return Negative errno on error, OK or positive value on success. + */ virtual int ioctl(int cmd, unsigned long arg) { return 0; } - rt_err_t register_driver(const char *devname, rt_uint16_t flags) { - rt_err_t ret = -1; - if (devname && !_registered) { - ret = rt_device_register(this, devname, flags); - - if (ret == RT_EOK) { - _registered = true; - } - } - - return ret; - } - - rt_err_t unregister_driver() { - rt_err_t ret = -1; - if (_registered) { - ret = rt_device_unregister(this); - if (ret == RT_EOK) { - _registered = false; - } - } - return ret; - } - - void lock() { - } - - void unlock() { - } - const char *get_devname() const { return _dev_name; } @@ -202,8 +166,13 @@ class Device : public rt_device { _dev_id.devid_s.devtype = devtype; } - // 总线类型,比如i2c + /** + * Return the bus type the device is connected to. + * + * @return The bus type + */ DeviceBusType get_device_bus_type() const { + // 总线类型,比如i2c return _dev_id.devid_s.bus_type; } @@ -248,8 +217,6 @@ class Device : public rt_device { // 设备id union DeviceId _dev_id {}; - bool _registered{false}; - // 驱动的名称,比如i2c1 const char *_bus_name{nullptr}; rt_device_t _bus_device{nullptr}; diff --git a/pkgs/device/i2c.cpp b/pkgs/device/i2c.cpp index 42c3b3c655..523f98c103 100644 --- a/pkgs/device/i2c.cpp +++ b/pkgs/device/i2c.cpp @@ -10,6 +10,8 @@ #include "i2c.hpp" +namespace nextpilot::device { + I2C::I2C(uint8_t device_type, const char *name, const int bus, const uint16_t address, const uint32_t frequency) : Device(name, nullptr), _frequency(frequency) { @@ -18,8 +20,6 @@ I2C::I2C(uint8_t device_type, const char *name, const int bus, const uint16_t ad _device_id.devid_s.bus_type = DeviceBusType_I2C; _device_id.devid_s.bus_index = bus; _device_id.devid_s.address = address; - - _device = rt_device_find(name); } // I2C::I2C(const I2CSPIDriverConfig &config) : @@ -33,8 +33,24 @@ I2C::~I2C() { } } -int init() { +int I2C::init() { + _dev = rt_device_find(""); + if (!_dev) { + return -RT_ERROR; + } + + if (probe() != RT_EOK) { + return -RT_ERROR; + } + + if (Device::init() != RT_EOK) { + return -RT_ERROR; + } + + return RT_EOK; } -int I2C::tansfer() { +int I2C::tansfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len) { } + +} // namespace nextpilot::device diff --git a/pkgs/device/i2c.hpp b/pkgs/device/i2c.hpp index 38a913bed6..fdec0d55b9 100644 --- a/pkgs/device/i2c.hpp +++ b/pkgs/device/i2c.hpp @@ -13,6 +13,8 @@ #include "device.hpp" +namespace nextpilot::device { + class I2C : pulbic Device { public: // no copy, assignment, move, move assignment @@ -48,7 +50,7 @@ class I2C : pulbic Device { * Check for the presence of the device on the bus. */ virtual int probe() { - return PX4_OK; + return 0; } /** @@ -76,4 +78,6 @@ class I2C : pulbic Device { rt_device_t *_dev{nullptr}; }; +} // namespace nextpilot::device + #endif // __I2C_H__ diff --git a/pkgs/device/rt-device.hpp b/pkgs/device/rt-device.hpp new file mode 100644 index 0000000000..5f9fd9cadd --- /dev/null +++ b/pkgs/device/rt-device.hpp @@ -0,0 +1,135 @@ +/***************************************************************** + * _ __ __ ____ _ __ __ + * / | / /___ _ __ / /_ / __ \ (_)/ /____ / /_ + * / |/ // _ \ | |/_// __// /_/ // // // __ \ / __/ + * / /| // __/_> < / /_ / ____// // // /_/ // /_ + * /_/ |_/ \___//_/|_| \__//_/ /_//_/ \____/ \__/ + * + * Copyright All Reserved © 2015-2024 NextPilot Development Team + ******************************************************************/ + +#ifndef __RT_DEVICE_H__ +#define __RT_DEVICE_H__ + +#include +#include + +class RTDevice; + +static rt_err_t _dev_init(rt_device_t dev) { + RTDevice *obj = (RTDevice *)dev; + return obj->init(); +} + +static rt_err_t _dev_open(rt_device_t dev, rt_uint16_t oflag) { + RTDevice *obj = (RTDevice *)dev; + return obj->open(oflag); +} + +static rt_err_t _dev_close(rt_device_t dev) { + RTDevice *obj = (RTDevice *)dev; + return obj->close(); +} + +static rt_ssize_t _dev_read(rt_device_t dev, rt_off_t pos, void *buffer, rt_size_t size) { + RTDevice *obj = (RTDevice *)dev; + return obj->read(pos, buffer, size); +} + +static rt_ssize_t _dev_write(rt_device_t dev, rt_off_t pos, const void *buffer, rt_size_t size) { + RTDevice *obj = (RTDevice *)dev; + return obj->write(pos, buffer, size); +} + +static rt_err_t _dev_control(rt_device_t dev, int cmd, void *args) { + RTDevice *obj = (RTDevice *)dev; + return obj->control(cmd, args); +} + +static rt_err_t _dev_register(rt_device_t dev) { +} + +#ifdef RT_USING_DEVICE_OPS +const struct rt_device_ops _dev_ops = { + .init = _dev_init, + .open = _dev_open, + .close = _dev_close, + .read = _dev_read, + .write = _dev_write, + .control = _dev_control, +}; +#endif // RT_USING_DEVICE_OPS + +class RTDevice : public rt_device { +public: + RTDevice() { + } + + RTDevice(const char *devname) : + _devname(devname) { + } + + rt_err_t _init_() { + type = RT_Device_Class_Char; + rx_indicate = nullptr; + tx_complete = nullptr; +#ifdef RT_USING_DEVICE_OPS + ops = &_dev_ops; +#else + init = _dev_init; + open = _dev_open; + close = _dev_close; + read = _dev_read; + write = _dev_write; + control = _dev_control; +#endif // RT_USING_DEVICE_OPS + fops = nullptr; + user_data = nullptr; + } + + virtual ~RTDevice() { + if (_registered) { + device_unregister(); + } + } + + virtual rt_err_t init() { + return RT_EOK; + } + + virtual rt_err_t open(rt_uint16_t oflag) { + return RT_EOK; + } + + virtual rt_err_t close() { + return RT_EOK; + } + + rt_ssize_t read(rt_off_t pos, void *buffer, rt_size_t size) { + return 0; + } + + rt_ssize_t write(rt_off_t pos, const void *buffer, rt_size_t size) { + return 0; + } + + rt_err_t control(int cmd, void *arg) { + return RT_EOK; + } + + rt_err_t device_register(const char *name, rt_uint16_t flags) { + _registered = true; + return rt_device_register(this, name, flags); + } + + rt_err_t device_unregister() { + _registered = false; + return rt_device_unregister(this); + } + +private: + const char *_devname{nullptr}; + bool _registered{false}; +}; + +#endif // __RT_DEVICE_H__ diff --git a/pkgs/param/interface/param_autogen.hpp b/pkgs/param/interface/param_autogen.hpp index a3293241e8..a1ddff8be9 100644 --- a/pkgs/param/interface/param_autogen.hpp +++ b/pkgs/param/interface/param_autogen.hpp @@ -919,876 +919,890 @@ enum class params_id : uint16_t { LTEST_SENS_ROT = 895, LTEST_VEL_UNC_IN = 896, MAN_ARM_GESTURE = 897, - MAV_0_CONFIG = 898, - MAV_0_FLOW_CTRL = 899, - MAV_0_FORWARD = 900, - MAV_0_MODE = 901, - MAV_0_RADIO_CTL = 902, - MAV_0_RATE = 903, - MAV_1_CONFIG = 904, - MAV_1_FLOW_CTRL = 905, - MAV_1_FORWARD = 906, - MAV_1_MODE = 907, - MAV_1_RADIO_CTL = 908, - MAV_1_RATE = 909, - MAV_2_CONFIG = 910, - MAV_2_FLOW_CTRL = 911, - MAV_2_FORWARD = 912, - MAV_2_MODE = 913, - MAV_2_RADIO_CTL = 914, - MAV_2_RATE = 915, - MAV_COMP_ID = 916, - MAV_FWDEXTSP = 917, - MAV_HASH_CHK_EN = 918, - MAV_HB_FORW_EN = 919, - MAV_PROTO_VER = 920, - MAV_RADIO_TOUT = 921, - MAV_SIK_RADIO_ID = 922, - MAV_SYS_ID = 923, - MAV_TYPE = 924, - MAV_USEHILGPS = 925, - MBE_ENABLE = 926, - MBE_LEARN_GAIN = 927, - MC_ACRO_EXPO = 928, - MC_ACRO_EXPO_Y = 929, - MC_ACRO_P_MAX = 930, - MC_ACRO_R_MAX = 931, - MC_ACRO_SUPEXPO = 932, - MC_ACRO_SUPEXPOY = 933, - MC_ACRO_Y_MAX = 934, - MC_AIRMODE = 935, - MC_AT_APPLY = 936, - MC_AT_EN = 937, - MC_AT_RISE_TIME = 938, - MC_AT_START = 939, - MC_AT_SYSID_AMP = 940, - MC_BAT_SCALE_EN = 941, - MC_MAN_TILT_TAU = 942, - MC_ORBIT_RAD_MAX = 943, - MC_PITCHRATE_D = 944, - MC_PITCHRATE_FF = 945, - MC_PITCHRATE_I = 946, - MC_PITCHRATE_K = 947, - MC_PITCHRATE_MAX = 948, - MC_PITCHRATE_P = 949, - MC_PITCH_P = 950, - MC_PR_INT_LIM = 951, - MC_ROLLRATE_D = 952, - MC_ROLLRATE_FF = 953, - MC_ROLLRATE_I = 954, - MC_ROLLRATE_K = 955, - MC_ROLLRATE_MAX = 956, - MC_ROLLRATE_P = 957, - MC_ROLL_P = 958, - MC_RR_INT_LIM = 959, - MC_YAWRATE_D = 960, - MC_YAWRATE_FF = 961, - MC_YAWRATE_I = 962, - MC_YAWRATE_K = 963, - MC_YAWRATE_MAX = 964, - MC_YAWRATE_P = 965, - MC_YAW_P = 966, - MC_YAW_WEIGHT = 967, - MC_YR_INT_LIM = 968, - MIS_DIST_1WP = 969, - MIS_LND_ABRT_ALT = 970, - MIS_MNT_YAW_CTL = 971, - MIS_PD_TO = 972, - MIS_TAKEOFF_ALT = 973, - MIS_TKO_LAND_REQ = 974, - MIS_YAW_ERR = 975, - MIS_YAW_TMT = 976, - MNT_DO_STAB = 977, - MNT_LND_P_MAX = 978, - MNT_LND_P_MIN = 979, - MNT_MAN_PITCH = 980, - MNT_MAN_ROLL = 981, - MNT_MAN_YAW = 982, - MNT_MAV_COMPID = 983, - MNT_MAV_SYSID = 984, - MNT_MODE_IN = 985, - MNT_MODE_OUT = 986, - MNT_OFF_PITCH = 987, - MNT_OFF_ROLL = 988, - MNT_OFF_YAW = 989, - MNT_RANGE_PITCH = 990, - MNT_RANGE_ROLL = 991, - MNT_RANGE_YAW = 992, - MNT_RATE_PITCH = 993, - MNT_RATE_YAW = 994, - MNT_RC_IN_MODE = 995, - MOT_SLEW_MAX = 996, - MPC_ACC_DOWN_MAX = 997, - MPC_ACC_HOR = 998, - MPC_ACC_HOR_MAX = 999, - MPC_ACC_UP_MAX = 1000, - MPC_ALT_MODE = 1001, - MPC_HOLD_DZ = 1002, - MPC_HOLD_MAX_XY = 1003, - MPC_HOLD_MAX_Z = 1004, - MPC_JERK_AUTO = 1005, - MPC_JERK_MAX = 1006, - MPC_LAND_ALT1 = 1007, - MPC_LAND_ALT2 = 1008, - MPC_LAND_ALT3 = 1009, - MPC_LAND_CRWL = 1010, - MPC_LAND_RADIUS = 1011, - MPC_LAND_RC_HELP = 1012, - MPC_LAND_SPEED = 1013, - MPC_MANTHR_MIN = 1014, - MPC_MAN_TILT_MAX = 1015, - MPC_MAN_Y_MAX = 1016, - MPC_MAN_Y_TAU = 1017, - MPC_POS_MODE = 1018, - MPC_THR_CURVE = 1019, - MPC_THR_HOVER = 1020, - MPC_THR_MAX = 1021, - MPC_THR_MIN = 1022, - MPC_THR_XY_MARG = 1023, - MPC_TILTMAX_AIR = 1024, - MPC_TILTMAX_LND = 1025, - MPC_TKO_RAMP_T = 1026, - MPC_TKO_SPEED = 1027, - MPC_USE_HTE = 1028, - MPC_VELD_LP = 1029, - MPC_VEL_MANUAL = 1030, - MPC_VEL_MAN_BACK = 1031, - MPC_VEL_MAN_SIDE = 1032, - MPC_XY_CRUISE = 1033, - MPC_XY_ERR_MAX = 1034, - MPC_XY_MAN_EXPO = 1035, - MPC_XY_P = 1036, - MPC_XY_TRAJ_P = 1037, - MPC_XY_VEL_ALL = 1038, - MPC_XY_VEL_D_ACC = 1039, - MPC_XY_VEL_I_ACC = 1040, - MPC_XY_VEL_MAX = 1041, - MPC_XY_VEL_P_ACC = 1042, - MPC_YAWRAUTO_MAX = 1043, - MPC_YAW_EXPO = 1044, - MPC_YAW_MODE = 1045, - MPC_Z_MAN_EXPO = 1046, - MPC_Z_P = 1047, - MPC_Z_VEL_ALL = 1048, - MPC_Z_VEL_D_ACC = 1049, - MPC_Z_VEL_I_ACC = 1050, - MPC_Z_VEL_MAX_DN = 1051, - MPC_Z_VEL_MAX_UP = 1052, - MPC_Z_VEL_P_ACC = 1053, - MPC_Z_V_AUTO_DN = 1054, - MPC_Z_V_AUTO_UP = 1055, - NAV_ACC_RAD = 1056, - NAV_DLL_ACT = 1057, - NAV_FORCE_VT = 1058, - NAV_FW_ALTL_RAD = 1059, - NAV_FW_ALT_RAD = 1060, - NAV_LOITER_RAD = 1061, - NAV_MC_ALT_RAD = 1062, - NAV_MIN_LTR_ALT = 1063, - NAV_RCL_ACT = 1064, - NAV_TRAFF_AVOID = 1065, - NAV_TRAFF_A_HOR = 1066, - NAV_TRAFF_A_VER = 1067, - NAV_TRAFF_COLL_T = 1068, - NPFG_DAMPING = 1069, - NPFG_EN_MIN_GSP = 1070, - NPFG_GSP_MAX_TK = 1071, - NPFG_LB_PERIOD = 1072, - NPFG_PERIOD = 1073, - NPFG_PERIOD_SF = 1074, - NPFG_ROLL_TC = 1075, - NPFG_SW_DST_MLT = 1076, - NPFG_TRACK_KEEP = 1077, - NPFG_UB_PERIOD = 1078, - NPFG_WIND_REG = 1079, - PD_GRIPPER_EN = 1080, - PD_GRIPPER_TO = 1081, - PD_GRIPPER_TYPE = 1082, - PLD_BTOUT = 1083, - PLD_FAPPR_ALT = 1084, - PLD_HACC_RAD = 1085, - PLD_MAX_SRCH = 1086, - PLD_SRCH_ALT = 1087, - PLD_SRCH_TOUT = 1088, - PPS_CAP_ENABLE = 1089, - RC10_DZ = 1090, - RC10_MAX = 1091, - RC10_MIN = 1092, - RC10_REV = 1093, - RC10_TRIM = 1094, - RC11_DZ = 1095, - RC11_MAX = 1096, - RC11_MIN = 1097, - RC11_REV = 1098, - RC11_TRIM = 1099, - RC12_DZ = 1100, - RC12_MAX = 1101, - RC12_MIN = 1102, - RC12_REV = 1103, - RC12_TRIM = 1104, - RC13_DZ = 1105, - RC13_MAX = 1106, - RC13_MIN = 1107, - RC13_REV = 1108, - RC13_TRIM = 1109, - RC14_DZ = 1110, - RC14_MAX = 1111, - RC14_MIN = 1112, - RC14_REV = 1113, - RC14_TRIM = 1114, - RC15_DZ = 1115, - RC15_MAX = 1116, - RC15_MIN = 1117, - RC15_REV = 1118, - RC15_TRIM = 1119, - RC16_DZ = 1120, - RC16_MAX = 1121, - RC16_MIN = 1122, - RC16_REV = 1123, - RC16_TRIM = 1124, - RC17_DZ = 1125, - RC17_MAX = 1126, - RC17_MIN = 1127, - RC17_REV = 1128, - RC17_TRIM = 1129, - RC18_DZ = 1130, - RC18_MAX = 1131, - RC18_MIN = 1132, - RC18_REV = 1133, - RC18_TRIM = 1134, - RC1_DZ = 1135, - RC1_MAX = 1136, - RC1_MIN = 1137, - RC1_REV = 1138, - RC1_TRIM = 1139, - RC2_DZ = 1140, - RC2_MAX = 1141, - RC2_MIN = 1142, - RC2_REV = 1143, - RC2_TRIM = 1144, - RC3_DZ = 1145, - RC3_MAX = 1146, - RC3_MIN = 1147, - RC3_REV = 1148, - RC3_TRIM = 1149, - RC4_DZ = 1150, - RC4_MAX = 1151, - RC4_MIN = 1152, - RC4_REV = 1153, - RC4_TRIM = 1154, - RC5_DZ = 1155, - RC5_MAX = 1156, - RC5_MIN = 1157, - RC5_REV = 1158, - RC5_TRIM = 1159, - RC6_DZ = 1160, - RC6_MAX = 1161, - RC6_MIN = 1162, - RC6_REV = 1163, - RC6_TRIM = 1164, - RC7_DZ = 1165, - RC7_MAX = 1166, - RC7_MIN = 1167, - RC7_REV = 1168, - RC7_TRIM = 1169, - RC8_DZ = 1170, - RC8_MAX = 1171, - RC8_MIN = 1172, - RC8_REV = 1173, - RC8_TRIM = 1174, - RC9_DZ = 1175, - RC9_MAX = 1176, - RC9_MIN = 1177, - RC9_REV = 1178, - RC9_TRIM = 1179, - RC_ARMSWITCH_TH = 1180, - RC_CHAN_CNT = 1181, - RC_ENG_MOT_TH = 1182, - RC_FAILS_THR = 1183, - RC_GEAR_TH = 1184, - RC_INPUT_PROTO = 1185, - RC_KILLSWITCH_TH = 1186, - RC_LOITER_TH = 1187, - RC_MAP_ACRO_SW = 1188, - RC_MAP_ARM_SW = 1189, - RC_MAP_AUX1 = 1190, - RC_MAP_AUX2 = 1191, - RC_MAP_AUX3 = 1192, - RC_MAP_AUX4 = 1193, - RC_MAP_AUX5 = 1194, - RC_MAP_AUX6 = 1195, - RC_MAP_ENG_MOT = 1196, - RC_MAP_FAILSAFE = 1197, - RC_MAP_FLAPS = 1198, - RC_MAP_FLTMODE = 1199, - RC_MAP_FLTM_BTN = 1200, - RC_MAP_GEAR_SW = 1201, - RC_MAP_KILL_SW = 1202, - RC_MAP_LOITER_SW = 1203, - RC_MAP_MAN_SW = 1204, - RC_MAP_MODE_SW = 1205, - RC_MAP_OFFB_SW = 1206, - RC_MAP_PARAM1 = 1207, - RC_MAP_PARAM2 = 1208, - RC_MAP_PARAM3 = 1209, - RC_MAP_PITCH = 1210, - RC_MAP_POSCTL_SW = 1211, - RC_MAP_RATT_SW = 1212, - RC_MAP_RETURN_SW = 1213, - RC_MAP_ROLL = 1214, - RC_MAP_STAB_SW = 1215, - RC_MAP_THROTTLE = 1216, - RC_MAP_TRANS_SW = 1217, - RC_MAP_YAW = 1218, - RC_OFFB_TH = 1219, - RC_RETURN_TH = 1220, - RC_RSSI_PWM_CHAN = 1221, - RC_RSSI_PWM_MAX = 1222, - RC_RSSI_PWM_MIN = 1223, - RC_TRANS_TH = 1224, - RTL_CONE_ANG = 1225, - RTL_DESCEND_ALT = 1226, - RTL_HDG_MD = 1227, - RTL_LAND_DELAY = 1228, - RTL_LOITER_RAD = 1229, - RTL_MIN_DIST = 1230, - RTL_PLD_MD = 1231, - RTL_RETURN_ALT = 1232, - RTL_TIME_FACTOR = 1233, - RTL_TIME_MARGIN = 1234, - RTL_TYPE = 1235, - RWTO_HDG = 1236, - RWTO_MAX_THR = 1237, - RWTO_NPFG_PERIOD = 1238, - RWTO_NUDGE = 1239, - RWTO_PSP = 1240, - RWTO_RAMP_TIME = 1241, - RWTO_ROT_AIRSPD = 1242, - RWTO_ROT_TIME = 1243, - RWTO_TKOFF = 1244, - SDLOG_ALGORITHM = 1245, - SDLOG_BOOT_BAT = 1246, - SDLOG_DIRS_MAX = 1247, - SDLOG_EXCH_KEY = 1248, - SDLOG_KEY = 1249, - SDLOG_MISSION = 1250, - SDLOG_MODE = 1251, - SDLOG_PROFILE = 1252, - SDLOG_UTC_OFFSET = 1253, - SDLOG_UUID = 1254, - SENS_BARO_QNH = 1255, - SENS_BARO_RATE = 1256, - SENS_BOARD_ROT = 1257, - SENS_BOARD_X_OFF = 1258, - SENS_BOARD_Y_OFF = 1259, - SENS_BOARD_Z_OFF = 1260, - SENS_DPRES_ANSC = 1261, - SENS_DPRES_OFF = 1262, - SENS_EN_ARSPDSIM = 1263, - SENS_EN_BAROSIM = 1264, - SENS_EN_BATT = 1265, - SENS_EN_GPSSIM = 1266, - SENS_EN_MAGSIM = 1267, - SENS_EN_MS4525DO = 1268, - SENS_EN_MS5525DS = 1269, - SENS_EN_PAA3905 = 1270, - SENS_EN_PAW3902 = 1271, - SENS_EN_PMW3901 = 1272, - SENS_EN_PX4FLOW = 1273, - SENS_EN_THERMAL = 1274, - SENS_EXT_I2C_PRB = 1275, - SENS_FLOW_MAXHGT = 1276, - SENS_FLOW_MAXR = 1277, - SENS_FLOW_MINHGT = 1278, - SENS_FLOW_RATE = 1279, - SENS_FLOW_ROT = 1280, - SENS_GPS_MASK = 1281, - SENS_GPS_PRIME = 1282, - SENS_GPS_TAU = 1283, - SENS_IMU_AUTOCAL = 1284, - SENS_IMU_MODE = 1285, - SENS_INT_BARO_EN = 1286, - SENS_MAG_AUTOCAL = 1287, - SENS_MAG_AUTOROT = 1288, - SENS_MAG_MODE = 1289, - SENS_MAG_RATE = 1290, - SENS_MAG_SIDES = 1291, - SIH_DISTSNSR_MAX = 1292, - SIH_DISTSNSR_MIN = 1293, - SIH_DISTSNSR_OVR = 1294, - SIH_IXX = 1295, - SIH_IXY = 1296, - SIH_IXZ = 1297, - SIH_IYY = 1298, - SIH_IYZ = 1299, - SIH_IZZ = 1300, - SIH_KDV = 1301, - SIH_KDW = 1302, - SIH_LOC_H0 = 1303, - SIH_LOC_LAT0 = 1304, - SIH_LOC_LON0 = 1305, - SIH_L_PITCH = 1306, - SIH_L_ROLL = 1307, - SIH_MASS = 1308, - SIH_Q_MAX = 1309, - SIH_T_MAX = 1310, - SIH_T_TAU = 1311, - SIH_VEHICLE_TYPE = 1312, - SIM_ARSPD_FAIL = 1313, - SIM_BARO_OFF_P = 1314, - SIM_BARO_OFF_T = 1315, - SIM_BAT_DRAIN = 1316, - SIM_BAT_MIN_PCT = 1317, - SIM_GPS_USED = 1318, - SIM_GZ_EC_DIS1 = 1319, - SIM_GZ_EC_DIS2 = 1320, - SIM_GZ_EC_DIS3 = 1321, - SIM_GZ_EC_DIS4 = 1322, - SIM_GZ_EC_DIS5 = 1323, - SIM_GZ_EC_DIS6 = 1324, - SIM_GZ_EC_DIS7 = 1325, - SIM_GZ_EC_DIS8 = 1326, - SIM_GZ_EC_FAIL1 = 1327, - SIM_GZ_EC_FAIL2 = 1328, - SIM_GZ_EC_FAIL3 = 1329, - SIM_GZ_EC_FAIL4 = 1330, - SIM_GZ_EC_FAIL5 = 1331, - SIM_GZ_EC_FAIL6 = 1332, - SIM_GZ_EC_FAIL7 = 1333, - SIM_GZ_EC_FAIL8 = 1334, - SIM_GZ_EC_FUNC1 = 1335, - SIM_GZ_EC_FUNC2 = 1336, - SIM_GZ_EC_FUNC3 = 1337, - SIM_GZ_EC_FUNC4 = 1338, - SIM_GZ_EC_FUNC5 = 1339, - SIM_GZ_EC_FUNC6 = 1340, - SIM_GZ_EC_FUNC7 = 1341, - SIM_GZ_EC_FUNC8 = 1342, - SIM_GZ_EC_MAX1 = 1343, - SIM_GZ_EC_MAX2 = 1344, - SIM_GZ_EC_MAX3 = 1345, - SIM_GZ_EC_MAX4 = 1346, - SIM_GZ_EC_MAX5 = 1347, - SIM_GZ_EC_MAX6 = 1348, - SIM_GZ_EC_MAX7 = 1349, - SIM_GZ_EC_MAX8 = 1350, - SIM_GZ_EC_MIN1 = 1351, - SIM_GZ_EC_MIN2 = 1352, - SIM_GZ_EC_MIN3 = 1353, - SIM_GZ_EC_MIN4 = 1354, - SIM_GZ_EC_MIN5 = 1355, - SIM_GZ_EC_MIN6 = 1356, - SIM_GZ_EC_MIN7 = 1357, - SIM_GZ_EC_MIN8 = 1358, - SIM_GZ_EC_REV = 1359, - SIM_GZ_EN = 1360, - SIM_GZ_HOME_ALT = 1361, - SIM_GZ_HOME_LAT = 1362, - SIM_GZ_HOME_LON = 1363, - SIM_GZ_SV_DIS1 = 1364, - SIM_GZ_SV_DIS2 = 1365, - SIM_GZ_SV_DIS3 = 1366, - SIM_GZ_SV_DIS4 = 1367, - SIM_GZ_SV_DIS5 = 1368, - SIM_GZ_SV_DIS6 = 1369, - SIM_GZ_SV_DIS7 = 1370, - SIM_GZ_SV_DIS8 = 1371, - SIM_GZ_SV_FAIL1 = 1372, - SIM_GZ_SV_FAIL2 = 1373, - SIM_GZ_SV_FAIL3 = 1374, - SIM_GZ_SV_FAIL4 = 1375, - SIM_GZ_SV_FAIL5 = 1376, - SIM_GZ_SV_FAIL6 = 1377, - SIM_GZ_SV_FAIL7 = 1378, - SIM_GZ_SV_FAIL8 = 1379, - SIM_GZ_SV_FUNC1 = 1380, - SIM_GZ_SV_FUNC2 = 1381, - SIM_GZ_SV_FUNC3 = 1382, - SIM_GZ_SV_FUNC4 = 1383, - SIM_GZ_SV_FUNC5 = 1384, - SIM_GZ_SV_FUNC6 = 1385, - SIM_GZ_SV_FUNC7 = 1386, - SIM_GZ_SV_FUNC8 = 1387, - SIM_GZ_SV_MAX1 = 1388, - SIM_GZ_SV_MAX2 = 1389, - SIM_GZ_SV_MAX3 = 1390, - SIM_GZ_SV_MAX4 = 1391, - SIM_GZ_SV_MAX5 = 1392, - SIM_GZ_SV_MAX6 = 1393, - SIM_GZ_SV_MAX7 = 1394, - SIM_GZ_SV_MAX8 = 1395, - SIM_GZ_SV_MIN1 = 1396, - SIM_GZ_SV_MIN2 = 1397, - SIM_GZ_SV_MIN3 = 1398, - SIM_GZ_SV_MIN4 = 1399, - SIM_GZ_SV_MIN5 = 1400, - SIM_GZ_SV_MIN6 = 1401, - SIM_GZ_SV_MIN7 = 1402, - SIM_GZ_SV_MIN8 = 1403, - SIM_GZ_SV_REV = 1404, - SIM_MAG_OFFSET_X = 1405, - SIM_MAG_OFFSET_Y = 1406, - SIM_MAG_OFFSET_Z = 1407, - SYS_AUTOCONFIG = 1408, - SYS_AUTOSTART = 1409, - SYS_BL_UPDATE = 1410, - SYS_CAL_ACCEL = 1411, - SYS_CAL_BARO = 1412, - SYS_CAL_GYRO = 1413, - SYS_CAL_TDEL = 1414, - SYS_CAL_TMAX = 1415, - SYS_CAL_TMIN = 1416, - SYS_DM_BACKEND = 1417, - SYS_FAC_CAL_MODE = 1418, - SYS_FAILURE_EN = 1419, - SYS_HAS_BARO = 1420, - SYS_HAS_GPS = 1421, - SYS_HAS_MAG = 1422, - SYS_HAS_NUM_DIST = 1423, - SYS_HITL = 1424, - SYS_MC_EST_GROUP = 1425, - SYS_RGB_MAXBRT = 1426, - SYS_STCK_EN = 1427, - SYS_VEHICLE_RESP = 1428, - SYS_VEHICLE_TYPE = 1429, - TC_A0_ID = 1430, - TC_A0_TMAX = 1431, - TC_A0_TMIN = 1432, - TC_A0_TREF = 1433, - TC_A0_X0_0 = 1434, - TC_A0_X0_1 = 1435, - TC_A0_X0_2 = 1436, - TC_A0_X1_0 = 1437, - TC_A0_X1_1 = 1438, - TC_A0_X1_2 = 1439, - TC_A0_X2_0 = 1440, - TC_A0_X2_1 = 1441, - TC_A0_X2_2 = 1442, - TC_A0_X3_0 = 1443, - TC_A0_X3_1 = 1444, - TC_A0_X3_2 = 1445, - TC_A1_ID = 1446, - TC_A1_TMAX = 1447, - TC_A1_TMIN = 1448, - TC_A1_TREF = 1449, - TC_A1_X0_0 = 1450, - TC_A1_X0_1 = 1451, - TC_A1_X0_2 = 1452, - TC_A1_X1_0 = 1453, - TC_A1_X1_1 = 1454, - TC_A1_X1_2 = 1455, - TC_A1_X2_0 = 1456, - TC_A1_X2_1 = 1457, - TC_A1_X2_2 = 1458, - TC_A1_X3_0 = 1459, - TC_A1_X3_1 = 1460, - TC_A1_X3_2 = 1461, - TC_A2_ID = 1462, - TC_A2_TMAX = 1463, - TC_A2_TMIN = 1464, - TC_A2_TREF = 1465, - TC_A2_X0_0 = 1466, - TC_A2_X0_1 = 1467, - TC_A2_X0_2 = 1468, - TC_A2_X1_0 = 1469, - TC_A2_X1_1 = 1470, - TC_A2_X1_2 = 1471, - TC_A2_X2_0 = 1472, - TC_A2_X2_1 = 1473, - TC_A2_X2_2 = 1474, - TC_A2_X3_0 = 1475, - TC_A2_X3_1 = 1476, - TC_A2_X3_2 = 1477, - TC_A3_ID = 1478, - TC_A3_TMAX = 1479, - TC_A3_TMIN = 1480, - TC_A3_TREF = 1481, - TC_A3_X0_0 = 1482, - TC_A3_X0_1 = 1483, - TC_A3_X0_2 = 1484, - TC_A3_X1_0 = 1485, - TC_A3_X1_1 = 1486, - TC_A3_X1_2 = 1487, - TC_A3_X2_0 = 1488, - TC_A3_X2_1 = 1489, - TC_A3_X2_2 = 1490, - TC_A3_X3_0 = 1491, - TC_A3_X3_1 = 1492, - TC_A3_X3_2 = 1493, - TC_A_ENABLE = 1494, - TC_B0_ID = 1495, - TC_B0_TMAX = 1496, - TC_B0_TMIN = 1497, - TC_B0_TREF = 1498, - TC_B0_X0 = 1499, - TC_B0_X1 = 1500, - TC_B0_X2 = 1501, - TC_B0_X3 = 1502, - TC_B0_X4 = 1503, - TC_B0_X5 = 1504, - TC_B1_ID = 1505, - TC_B1_TMAX = 1506, - TC_B1_TMIN = 1507, - TC_B1_TREF = 1508, - TC_B1_X0 = 1509, - TC_B1_X1 = 1510, - TC_B1_X2 = 1511, - TC_B1_X3 = 1512, - TC_B1_X4 = 1513, - TC_B1_X5 = 1514, - TC_B2_ID = 1515, - TC_B2_TMAX = 1516, - TC_B2_TMIN = 1517, - TC_B2_TREF = 1518, - TC_B2_X0 = 1519, - TC_B2_X1 = 1520, - TC_B2_X2 = 1521, - TC_B2_X3 = 1522, - TC_B2_X4 = 1523, - TC_B2_X5 = 1524, - TC_B3_ID = 1525, - TC_B3_TMAX = 1526, - TC_B3_TMIN = 1527, - TC_B3_TREF = 1528, - TC_B3_X0 = 1529, - TC_B3_X1 = 1530, - TC_B3_X2 = 1531, - TC_B3_X3 = 1532, - TC_B3_X4 = 1533, - TC_B3_X5 = 1534, - TC_B_ENABLE = 1535, - TC_G0_ID = 1536, - TC_G0_TMAX = 1537, - TC_G0_TMIN = 1538, - TC_G0_TREF = 1539, - TC_G0_X0_0 = 1540, - TC_G0_X0_1 = 1541, - TC_G0_X0_2 = 1542, - TC_G0_X1_0 = 1543, - TC_G0_X1_1 = 1544, - TC_G0_X1_2 = 1545, - TC_G0_X2_0 = 1546, - TC_G0_X2_1 = 1547, - TC_G0_X2_2 = 1548, - TC_G0_X3_0 = 1549, - TC_G0_X3_1 = 1550, - TC_G0_X3_2 = 1551, - TC_G1_ID = 1552, - TC_G1_TMAX = 1553, - TC_G1_TMIN = 1554, - TC_G1_TREF = 1555, - TC_G1_X0_0 = 1556, - TC_G1_X0_1 = 1557, - TC_G1_X0_2 = 1558, - TC_G1_X1_0 = 1559, - TC_G1_X1_1 = 1560, - TC_G1_X1_2 = 1561, - TC_G1_X2_0 = 1562, - TC_G1_X2_1 = 1563, - TC_G1_X2_2 = 1564, - TC_G1_X3_0 = 1565, - TC_G1_X3_1 = 1566, - TC_G1_X3_2 = 1567, - TC_G2_ID = 1568, - TC_G2_TMAX = 1569, - TC_G2_TMIN = 1570, - TC_G2_TREF = 1571, - TC_G2_X0_0 = 1572, - TC_G2_X0_1 = 1573, - TC_G2_X0_2 = 1574, - TC_G2_X1_0 = 1575, - TC_G2_X1_1 = 1576, - TC_G2_X1_2 = 1577, - TC_G2_X2_0 = 1578, - TC_G2_X2_1 = 1579, - TC_G2_X2_2 = 1580, - TC_G2_X3_0 = 1581, - TC_G2_X3_1 = 1582, - TC_G2_X3_2 = 1583, - TC_G3_ID = 1584, - TC_G3_TMAX = 1585, - TC_G3_TMIN = 1586, - TC_G3_TREF = 1587, - TC_G3_X0_0 = 1588, - TC_G3_X0_1 = 1589, - TC_G3_X0_2 = 1590, - TC_G3_X1_0 = 1591, - TC_G3_X1_1 = 1592, - TC_G3_X1_2 = 1593, - TC_G3_X2_0 = 1594, - TC_G3_X2_1 = 1595, - TC_G3_X2_2 = 1596, - TC_G3_X3_0 = 1597, - TC_G3_X3_1 = 1598, - TC_G3_X3_2 = 1599, - TC_G_ENABLE = 1600, - TEST_D = 1601, - TEST_DEV = 1602, - TEST_D_LP = 1603, - TEST_HP = 1604, - TEST_I = 1605, - TEST_I_MAX = 1606, - TEST_LP = 1607, - TEST_MAX = 1608, - TEST_MEAN = 1609, - TEST_MIN = 1610, - TEST_P = 1611, - TEST_TRIM = 1612, - THR_MDL_FAC = 1613, - TRIG_ACT_TIME = 1614, - TRIG_DISTANCE = 1615, - TRIG_INTERFACE = 1616, - TRIG_INTERVAL = 1617, - TRIG_MIN_INTERVA = 1618, - TRIG_MODE = 1619, - TRIG_POLARITY = 1620, - TRIG_PWM_NEUTRAL = 1621, - TRIG_PWM_SHOOT = 1622, - TRIM_PITCH = 1623, - TRIM_ROLL = 1624, - TRIM_YAW = 1625, - UAVCAN_BITRATE = 1626, - UAVCAN_EC_FAIL1 = 1627, - UAVCAN_EC_FAIL2 = 1628, - UAVCAN_EC_FAIL3 = 1629, - UAVCAN_EC_FAIL4 = 1630, - UAVCAN_EC_FAIL5 = 1631, - UAVCAN_EC_FAIL6 = 1632, - UAVCAN_EC_FAIL7 = 1633, - UAVCAN_EC_FAIL8 = 1634, - UAVCAN_EC_FUNC1 = 1635, - UAVCAN_EC_FUNC2 = 1636, - UAVCAN_EC_FUNC3 = 1637, - UAVCAN_EC_FUNC4 = 1638, - UAVCAN_EC_FUNC5 = 1639, - UAVCAN_EC_FUNC6 = 1640, - UAVCAN_EC_FUNC7 = 1641, - UAVCAN_EC_FUNC8 = 1642, - UAVCAN_EC_MAX1 = 1643, - UAVCAN_EC_MAX2 = 1644, - UAVCAN_EC_MAX3 = 1645, - UAVCAN_EC_MAX4 = 1646, - UAVCAN_EC_MAX5 = 1647, - UAVCAN_EC_MAX6 = 1648, - UAVCAN_EC_MAX7 = 1649, - UAVCAN_EC_MAX8 = 1650, - UAVCAN_EC_MIN1 = 1651, - UAVCAN_EC_MIN2 = 1652, - UAVCAN_EC_MIN3 = 1653, - UAVCAN_EC_MIN4 = 1654, - UAVCAN_EC_MIN5 = 1655, - UAVCAN_EC_MIN6 = 1656, - UAVCAN_EC_MIN7 = 1657, - UAVCAN_EC_MIN8 = 1658, - UAVCAN_EC_REV = 1659, - UAVCAN_ENABLE = 1660, - UAVCAN_LGT_ANTCL = 1661, - UAVCAN_LGT_LAND = 1662, - UAVCAN_LGT_NAV = 1663, - UAVCAN_LGT_STROB = 1664, - UAVCAN_NODE_ID = 1665, - UAVCAN_PUB_ARM = 1666, - UAVCAN_PUB_MBD = 1667, - UAVCAN_PUB_RTCM = 1668, - UAVCAN_RNG_MAX = 1669, - UAVCAN_RNG_MIN = 1670, - UAVCAN_SUB_ASPD = 1671, - UAVCAN_SUB_BARO = 1672, - UAVCAN_SUB_BAT = 1673, - UAVCAN_SUB_BTN = 1674, - UAVCAN_SUB_DPRES = 1675, - UAVCAN_SUB_FLOW = 1676, - UAVCAN_SUB_GPS = 1677, - UAVCAN_SUB_HYGRO = 1678, - UAVCAN_SUB_ICE = 1679, - UAVCAN_SUB_IMU = 1680, - UAVCAN_SUB_MAG = 1681, - UAVCAN_SUB_RNG = 1682, - UAVCAN_SV_DIS1 = 1683, - UAVCAN_SV_DIS2 = 1684, - UAVCAN_SV_DIS3 = 1685, - UAVCAN_SV_DIS4 = 1686, - UAVCAN_SV_DIS5 = 1687, - UAVCAN_SV_DIS6 = 1688, - UAVCAN_SV_DIS7 = 1689, - UAVCAN_SV_DIS8 = 1690, - UAVCAN_SV_FAIL1 = 1691, - UAVCAN_SV_FAIL2 = 1692, - UAVCAN_SV_FAIL3 = 1693, - UAVCAN_SV_FAIL4 = 1694, - UAVCAN_SV_FAIL5 = 1695, - UAVCAN_SV_FAIL6 = 1696, - UAVCAN_SV_FAIL7 = 1697, - UAVCAN_SV_FAIL8 = 1698, - UAVCAN_SV_FUNC1 = 1699, - UAVCAN_SV_FUNC2 = 1700, - UAVCAN_SV_FUNC3 = 1701, - UAVCAN_SV_FUNC4 = 1702, - UAVCAN_SV_FUNC5 = 1703, - UAVCAN_SV_FUNC6 = 1704, - UAVCAN_SV_FUNC7 = 1705, - UAVCAN_SV_FUNC8 = 1706, - UAVCAN_SV_MAX1 = 1707, - UAVCAN_SV_MAX2 = 1708, - UAVCAN_SV_MAX3 = 1709, - UAVCAN_SV_MAX4 = 1710, - UAVCAN_SV_MAX5 = 1711, - UAVCAN_SV_MAX6 = 1712, - UAVCAN_SV_MAX7 = 1713, - UAVCAN_SV_MAX8 = 1714, - UAVCAN_SV_MIN1 = 1715, - UAVCAN_SV_MIN2 = 1716, - UAVCAN_SV_MIN3 = 1717, - UAVCAN_SV_MIN4 = 1718, - UAVCAN_SV_MIN5 = 1719, - UAVCAN_SV_MIN6 = 1720, - UAVCAN_SV_MIN7 = 1721, - UAVCAN_SV_MIN8 = 1722, - UAVCAN_SV_REV = 1723, - UXRCE_DDS_DOM_ID = 1724, - UXRCE_DDS_KEY = 1725, - VTO_LOITER_ALT = 1726, - VT_ARSP_BLEND = 1727, - VT_ARSP_TRANS = 1728, - VT_B_DEC_FF = 1729, - VT_B_DEC_I = 1730, - VT_B_DEC_MSS = 1731, - VT_B_TRANS_DUR = 1732, - VT_B_TRANS_RAMP = 1733, - VT_ELEV_MC_LOCK = 1734, - VT_FWD_THRUST_EN = 1735, - VT_FWD_THRUST_SC = 1736, - VT_FW_DIFTHR_EN = 1737, - VT_FW_DIFTHR_S_P = 1738, - VT_FW_DIFTHR_S_R = 1739, - VT_FW_DIFTHR_S_Y = 1740, - VT_FW_MIN_ALT = 1741, - VT_FW_QC_HMAX = 1742, - VT_FW_QC_P = 1743, - VT_FW_QC_R = 1744, - VT_F_TRANS_DUR = 1745, - VT_F_TRANS_THR = 1746, - VT_F_TR_OL_TM = 1747, - VT_LND_PITCH_MIN = 1748, - VT_PITCH_MIN = 1749, - VT_PSHER_SLEW = 1750, - VT_QC_ALT_LOSS = 1751, - VT_QC_T_ALT_LOSS = 1752, - VT_SPOILER_MC_LD = 1753, - VT_TILT_FW = 1754, - VT_TILT_MC = 1755, - VT_TILT_SPINUP = 1756, - VT_TILT_TRANS = 1757, - VT_TRANS_MIN_TM = 1758, - VT_TRANS_P2_DUR = 1759, - VT_TRANS_TIMEOUT = 1760, - VT_TYPE = 1761, - WEIGHT_BASE = 1762, - WEIGHT_GROSS = 1763, - WV_EN = 1764, - WV_GAIN = 1765, - WV_ROLL_MIN = 1766, - WV_YRATE_MAX = 1767, + MAV_0_BROADCAST = 898, + MAV_0_CONFIG = 899, + MAV_0_FLOW_CTRL = 900, + MAV_0_FORWARD = 901, + MAV_0_MODE = 902, + MAV_0_RADIO_CTL = 903, + MAV_0_RATE = 904, + MAV_0_REMOTE_IP = 905, + MAV_0_REMOTE_PRT = 906, + MAV_0_UDP_PRT = 907, + MAV_1_BROADCAST = 908, + MAV_1_CONFIG = 909, + MAV_1_FLOW_CTRL = 910, + MAV_1_FORWARD = 911, + MAV_1_MODE = 912, + MAV_1_RADIO_CTL = 913, + MAV_1_RATE = 914, + MAV_1_REMOTE_IP = 915, + MAV_1_REMOTE_PRT = 916, + MAV_1_UDP_PRT = 917, + MAV_2_BROADCAST = 918, + MAV_2_CONFIG = 919, + MAV_2_FLOW_CTRL = 920, + MAV_2_FORWARD = 921, + MAV_2_MODE = 922, + MAV_2_RADIO_CTL = 923, + MAV_2_RATE = 924, + MAV_2_REMOTE_IP = 925, + MAV_2_REMOTE_PRT = 926, + MAV_2_UDP_PRT = 927, + MAV_COMP_ID = 928, + MAV_FWDEXTSP = 929, + MAV_HASH_CHK_EN = 930, + MAV_HB_FORW_EN = 931, + MAV_PROTO_VER = 932, + MAV_RADIO_TOUT = 933, + MAV_SIK_RADIO_ID = 934, + MAV_SYS_ID = 935, + MAV_TYPE = 936, + MAV_USEHILGPS = 937, + MBE_ENABLE = 938, + MBE_LEARN_GAIN = 939, + MC_ACRO_EXPO = 940, + MC_ACRO_EXPO_Y = 941, + MC_ACRO_P_MAX = 942, + MC_ACRO_R_MAX = 943, + MC_ACRO_SUPEXPO = 944, + MC_ACRO_SUPEXPOY = 945, + MC_ACRO_Y_MAX = 946, + MC_AIRMODE = 947, + MC_AT_APPLY = 948, + MC_AT_EN = 949, + MC_AT_RISE_TIME = 950, + MC_AT_START = 951, + MC_AT_SYSID_AMP = 952, + MC_BAT_SCALE_EN = 953, + MC_MAN_TILT_TAU = 954, + MC_ORBIT_RAD_MAX = 955, + MC_PITCHRATE_D = 956, + MC_PITCHRATE_FF = 957, + MC_PITCHRATE_I = 958, + MC_PITCHRATE_K = 959, + MC_PITCHRATE_MAX = 960, + MC_PITCHRATE_P = 961, + MC_PITCH_P = 962, + MC_PR_INT_LIM = 963, + MC_ROLLRATE_D = 964, + MC_ROLLRATE_FF = 965, + MC_ROLLRATE_I = 966, + MC_ROLLRATE_K = 967, + MC_ROLLRATE_MAX = 968, + MC_ROLLRATE_P = 969, + MC_ROLL_P = 970, + MC_RR_INT_LIM = 971, + MC_YAWRATE_D = 972, + MC_YAWRATE_FF = 973, + MC_YAWRATE_I = 974, + MC_YAWRATE_K = 975, + MC_YAWRATE_MAX = 976, + MC_YAWRATE_P = 977, + MC_YAW_P = 978, + MC_YAW_WEIGHT = 979, + MC_YR_INT_LIM = 980, + MIS_DIST_1WP = 981, + MIS_LND_ABRT_ALT = 982, + MIS_MNT_YAW_CTL = 983, + MIS_PD_TO = 984, + MIS_TAKEOFF_ALT = 985, + MIS_TKO_LAND_REQ = 986, + MIS_YAW_ERR = 987, + MIS_YAW_TMT = 988, + MNT_DO_STAB = 989, + MNT_LND_P_MAX = 990, + MNT_LND_P_MIN = 991, + MNT_MAN_PITCH = 992, + MNT_MAN_ROLL = 993, + MNT_MAN_YAW = 994, + MNT_MAV_COMPID = 995, + MNT_MAV_SYSID = 996, + MNT_MODE_IN = 997, + MNT_MODE_OUT = 998, + MNT_OFF_PITCH = 999, + MNT_OFF_ROLL = 1000, + MNT_OFF_YAW = 1001, + MNT_RANGE_PITCH = 1002, + MNT_RANGE_ROLL = 1003, + MNT_RANGE_YAW = 1004, + MNT_RATE_PITCH = 1005, + MNT_RATE_YAW = 1006, + MNT_RC_IN_MODE = 1007, + MOT_SLEW_MAX = 1008, + MPC_ACC_DOWN_MAX = 1009, + MPC_ACC_HOR = 1010, + MPC_ACC_HOR_MAX = 1011, + MPC_ACC_UP_MAX = 1012, + MPC_ALT_MODE = 1013, + MPC_HOLD_DZ = 1014, + MPC_HOLD_MAX_XY = 1015, + MPC_HOLD_MAX_Z = 1016, + MPC_JERK_AUTO = 1017, + MPC_JERK_MAX = 1018, + MPC_LAND_ALT1 = 1019, + MPC_LAND_ALT2 = 1020, + MPC_LAND_ALT3 = 1021, + MPC_LAND_CRWL = 1022, + MPC_LAND_RADIUS = 1023, + MPC_LAND_RC_HELP = 1024, + MPC_LAND_SPEED = 1025, + MPC_MANTHR_MIN = 1026, + MPC_MAN_TILT_MAX = 1027, + MPC_MAN_Y_MAX = 1028, + MPC_MAN_Y_TAU = 1029, + MPC_POS_MODE = 1030, + MPC_THR_CURVE = 1031, + MPC_THR_HOVER = 1032, + MPC_THR_MAX = 1033, + MPC_THR_MIN = 1034, + MPC_THR_XY_MARG = 1035, + MPC_TILTMAX_AIR = 1036, + MPC_TILTMAX_LND = 1037, + MPC_TKO_RAMP_T = 1038, + MPC_TKO_SPEED = 1039, + MPC_USE_HTE = 1040, + MPC_VELD_LP = 1041, + MPC_VEL_MANUAL = 1042, + MPC_VEL_MAN_BACK = 1043, + MPC_VEL_MAN_SIDE = 1044, + MPC_XY_CRUISE = 1045, + MPC_XY_ERR_MAX = 1046, + MPC_XY_MAN_EXPO = 1047, + MPC_XY_P = 1048, + MPC_XY_TRAJ_P = 1049, + MPC_XY_VEL_ALL = 1050, + MPC_XY_VEL_D_ACC = 1051, + MPC_XY_VEL_I_ACC = 1052, + MPC_XY_VEL_MAX = 1053, + MPC_XY_VEL_P_ACC = 1054, + MPC_YAWRAUTO_MAX = 1055, + MPC_YAW_EXPO = 1056, + MPC_YAW_MODE = 1057, + MPC_Z_MAN_EXPO = 1058, + MPC_Z_P = 1059, + MPC_Z_VEL_ALL = 1060, + MPC_Z_VEL_D_ACC = 1061, + MPC_Z_VEL_I_ACC = 1062, + MPC_Z_VEL_MAX_DN = 1063, + MPC_Z_VEL_MAX_UP = 1064, + MPC_Z_VEL_P_ACC = 1065, + MPC_Z_V_AUTO_DN = 1066, + MPC_Z_V_AUTO_UP = 1067, + NAV_ACC_RAD = 1068, + NAV_DLL_ACT = 1069, + NAV_FORCE_VT = 1070, + NAV_FW_ALTL_RAD = 1071, + NAV_FW_ALT_RAD = 1072, + NAV_LOITER_RAD = 1073, + NAV_MC_ALT_RAD = 1074, + NAV_MIN_LTR_ALT = 1075, + NAV_RCL_ACT = 1076, + NAV_TRAFF_AVOID = 1077, + NAV_TRAFF_A_HOR = 1078, + NAV_TRAFF_A_VER = 1079, + NAV_TRAFF_COLL_T = 1080, + NPFG_DAMPING = 1081, + NPFG_EN_MIN_GSP = 1082, + NPFG_GSP_MAX_TK = 1083, + NPFG_LB_PERIOD = 1084, + NPFG_PERIOD = 1085, + NPFG_PERIOD_SF = 1086, + NPFG_ROLL_TC = 1087, + NPFG_SW_DST_MLT = 1088, + NPFG_TRACK_KEEP = 1089, + NPFG_UB_PERIOD = 1090, + NPFG_WIND_REG = 1091, + PD_GRIPPER_EN = 1092, + PD_GRIPPER_TO = 1093, + PD_GRIPPER_TYPE = 1094, + PLD_BTOUT = 1095, + PLD_FAPPR_ALT = 1096, + PLD_HACC_RAD = 1097, + PLD_MAX_SRCH = 1098, + PLD_SRCH_ALT = 1099, + PLD_SRCH_TOUT = 1100, + PPS_CAP_ENABLE = 1101, + RC10_DZ = 1102, + RC10_MAX = 1103, + RC10_MIN = 1104, + RC10_REV = 1105, + RC10_TRIM = 1106, + RC11_DZ = 1107, + RC11_MAX = 1108, + RC11_MIN = 1109, + RC11_REV = 1110, + RC11_TRIM = 1111, + RC12_DZ = 1112, + RC12_MAX = 1113, + RC12_MIN = 1114, + RC12_REV = 1115, + RC12_TRIM = 1116, + RC13_DZ = 1117, + RC13_MAX = 1118, + RC13_MIN = 1119, + RC13_REV = 1120, + RC13_TRIM = 1121, + RC14_DZ = 1122, + RC14_MAX = 1123, + RC14_MIN = 1124, + RC14_REV = 1125, + RC14_TRIM = 1126, + RC15_DZ = 1127, + RC15_MAX = 1128, + RC15_MIN = 1129, + RC15_REV = 1130, + RC15_TRIM = 1131, + RC16_DZ = 1132, + RC16_MAX = 1133, + RC16_MIN = 1134, + RC16_REV = 1135, + RC16_TRIM = 1136, + RC17_DZ = 1137, + RC17_MAX = 1138, + RC17_MIN = 1139, + RC17_REV = 1140, + RC17_TRIM = 1141, + RC18_DZ = 1142, + RC18_MAX = 1143, + RC18_MIN = 1144, + RC18_REV = 1145, + RC18_TRIM = 1146, + RC1_DZ = 1147, + RC1_MAX = 1148, + RC1_MIN = 1149, + RC1_REV = 1150, + RC1_TRIM = 1151, + RC2_DZ = 1152, + RC2_MAX = 1153, + RC2_MIN = 1154, + RC2_REV = 1155, + RC2_TRIM = 1156, + RC3_DZ = 1157, + RC3_MAX = 1158, + RC3_MIN = 1159, + RC3_REV = 1160, + RC3_TRIM = 1161, + RC4_DZ = 1162, + RC4_MAX = 1163, + RC4_MIN = 1164, + RC4_REV = 1165, + RC4_TRIM = 1166, + RC5_DZ = 1167, + RC5_MAX = 1168, + RC5_MIN = 1169, + RC5_REV = 1170, + RC5_TRIM = 1171, + RC6_DZ = 1172, + RC6_MAX = 1173, + RC6_MIN = 1174, + RC6_REV = 1175, + RC6_TRIM = 1176, + RC7_DZ = 1177, + RC7_MAX = 1178, + RC7_MIN = 1179, + RC7_REV = 1180, + RC7_TRIM = 1181, + RC8_DZ = 1182, + RC8_MAX = 1183, + RC8_MIN = 1184, + RC8_REV = 1185, + RC8_TRIM = 1186, + RC9_DZ = 1187, + RC9_MAX = 1188, + RC9_MIN = 1189, + RC9_REV = 1190, + RC9_TRIM = 1191, + RC_ARMSWITCH_TH = 1192, + RC_CHAN_CNT = 1193, + RC_ENG_MOT_TH = 1194, + RC_FAILS_THR = 1195, + RC_GEAR_TH = 1196, + RC_INPUT_PROTO = 1197, + RC_KILLSWITCH_TH = 1198, + RC_LOITER_TH = 1199, + RC_MAP_ACRO_SW = 1200, + RC_MAP_ARM_SW = 1201, + RC_MAP_AUX1 = 1202, + RC_MAP_AUX2 = 1203, + RC_MAP_AUX3 = 1204, + RC_MAP_AUX4 = 1205, + RC_MAP_AUX5 = 1206, + RC_MAP_AUX6 = 1207, + RC_MAP_ENG_MOT = 1208, + RC_MAP_FAILSAFE = 1209, + RC_MAP_FLAPS = 1210, + RC_MAP_FLTMODE = 1211, + RC_MAP_FLTM_BTN = 1212, + RC_MAP_GEAR_SW = 1213, + RC_MAP_KILL_SW = 1214, + RC_MAP_LOITER_SW = 1215, + RC_MAP_MAN_SW = 1216, + RC_MAP_MODE_SW = 1217, + RC_MAP_OFFB_SW = 1218, + RC_MAP_PARAM1 = 1219, + RC_MAP_PARAM2 = 1220, + RC_MAP_PARAM3 = 1221, + RC_MAP_PITCH = 1222, + RC_MAP_POSCTL_SW = 1223, + RC_MAP_RATT_SW = 1224, + RC_MAP_RETURN_SW = 1225, + RC_MAP_ROLL = 1226, + RC_MAP_STAB_SW = 1227, + RC_MAP_THROTTLE = 1228, + RC_MAP_TRANS_SW = 1229, + RC_MAP_YAW = 1230, + RC_OFFB_TH = 1231, + RC_RETURN_TH = 1232, + RC_RSSI_PWM_CHAN = 1233, + RC_RSSI_PWM_MAX = 1234, + RC_RSSI_PWM_MIN = 1235, + RC_TRANS_TH = 1236, + RTL_CONE_ANG = 1237, + RTL_DESCEND_ALT = 1238, + RTL_HDG_MD = 1239, + RTL_LAND_DELAY = 1240, + RTL_LOITER_RAD = 1241, + RTL_MIN_DIST = 1242, + RTL_PLD_MD = 1243, + RTL_RETURN_ALT = 1244, + RTL_TIME_FACTOR = 1245, + RTL_TIME_MARGIN = 1246, + RTL_TYPE = 1247, + RWTO_HDG = 1248, + RWTO_MAX_THR = 1249, + RWTO_NPFG_PERIOD = 1250, + RWTO_NUDGE = 1251, + RWTO_PSP = 1252, + RWTO_RAMP_TIME = 1253, + RWTO_ROT_AIRSPD = 1254, + RWTO_ROT_TIME = 1255, + RWTO_TKOFF = 1256, + SDLOG_ALGORITHM = 1257, + SDLOG_BOOT_BAT = 1258, + SDLOG_DIRS_MAX = 1259, + SDLOG_EXCH_KEY = 1260, + SDLOG_KEY = 1261, + SDLOG_MISSION = 1262, + SDLOG_MODE = 1263, + SDLOG_PROFILE = 1264, + SDLOG_UTC_OFFSET = 1265, + SDLOG_UUID = 1266, + SENS_BARO_QNH = 1267, + SENS_BARO_RATE = 1268, + SENS_BOARD_ROT = 1269, + SENS_BOARD_X_OFF = 1270, + SENS_BOARD_Y_OFF = 1271, + SENS_BOARD_Z_OFF = 1272, + SENS_DPRES_ANSC = 1273, + SENS_DPRES_OFF = 1274, + SENS_EN_ARSPDSIM = 1275, + SENS_EN_BAROSIM = 1276, + SENS_EN_BATT = 1277, + SENS_EN_GPSSIM = 1278, + SENS_EN_MAGSIM = 1279, + SENS_EN_MS4525DO = 1280, + SENS_EN_MS5525DS = 1281, + SENS_EN_PAA3905 = 1282, + SENS_EN_PAW3902 = 1283, + SENS_EN_PMW3901 = 1284, + SENS_EN_PX4FLOW = 1285, + SENS_EN_THERMAL = 1286, + SENS_EXT_I2C_PRB = 1287, + SENS_FLOW_MAXHGT = 1288, + SENS_FLOW_MAXR = 1289, + SENS_FLOW_MINHGT = 1290, + SENS_FLOW_RATE = 1291, + SENS_FLOW_ROT = 1292, + SENS_GPS_MASK = 1293, + SENS_GPS_PRIME = 1294, + SENS_GPS_TAU = 1295, + SENS_IMU_AUTOCAL = 1296, + SENS_IMU_MODE = 1297, + SENS_INT_BARO_EN = 1298, + SENS_MAG_AUTOCAL = 1299, + SENS_MAG_AUTOROT = 1300, + SENS_MAG_MODE = 1301, + SENS_MAG_RATE = 1302, + SENS_MAG_SIDES = 1303, + SIH_DISTSNSR_MAX = 1304, + SIH_DISTSNSR_MIN = 1305, + SIH_DISTSNSR_OVR = 1306, + SIH_IXX = 1307, + SIH_IXY = 1308, + SIH_IXZ = 1309, + SIH_IYY = 1310, + SIH_IYZ = 1311, + SIH_IZZ = 1312, + SIH_KDV = 1313, + SIH_KDW = 1314, + SIH_LOC_H0 = 1315, + SIH_LOC_LAT0 = 1316, + SIH_LOC_LON0 = 1317, + SIH_L_PITCH = 1318, + SIH_L_ROLL = 1319, + SIH_MASS = 1320, + SIH_Q_MAX = 1321, + SIH_T_MAX = 1322, + SIH_T_TAU = 1323, + SIH_VEHICLE_TYPE = 1324, + SIM_ARSPD_FAIL = 1325, + SIM_BARO_OFF_P = 1326, + SIM_BARO_OFF_T = 1327, + SIM_BAT_DRAIN = 1328, + SIM_BAT_MIN_PCT = 1329, + SIM_GPS_USED = 1330, + SIM_GZ_EC_DIS1 = 1331, + SIM_GZ_EC_DIS2 = 1332, + SIM_GZ_EC_DIS3 = 1333, + SIM_GZ_EC_DIS4 = 1334, + SIM_GZ_EC_DIS5 = 1335, + SIM_GZ_EC_DIS6 = 1336, + SIM_GZ_EC_DIS7 = 1337, + SIM_GZ_EC_DIS8 = 1338, + SIM_GZ_EC_FAIL1 = 1339, + SIM_GZ_EC_FAIL2 = 1340, + SIM_GZ_EC_FAIL3 = 1341, + SIM_GZ_EC_FAIL4 = 1342, + SIM_GZ_EC_FAIL5 = 1343, + SIM_GZ_EC_FAIL6 = 1344, + SIM_GZ_EC_FAIL7 = 1345, + SIM_GZ_EC_FAIL8 = 1346, + SIM_GZ_EC_FUNC1 = 1347, + SIM_GZ_EC_FUNC2 = 1348, + SIM_GZ_EC_FUNC3 = 1349, + SIM_GZ_EC_FUNC4 = 1350, + SIM_GZ_EC_FUNC5 = 1351, + SIM_GZ_EC_FUNC6 = 1352, + SIM_GZ_EC_FUNC7 = 1353, + SIM_GZ_EC_FUNC8 = 1354, + SIM_GZ_EC_MAX1 = 1355, + SIM_GZ_EC_MAX2 = 1356, + SIM_GZ_EC_MAX3 = 1357, + SIM_GZ_EC_MAX4 = 1358, + SIM_GZ_EC_MAX5 = 1359, + SIM_GZ_EC_MAX6 = 1360, + SIM_GZ_EC_MAX7 = 1361, + SIM_GZ_EC_MAX8 = 1362, + SIM_GZ_EC_MIN1 = 1363, + SIM_GZ_EC_MIN2 = 1364, + SIM_GZ_EC_MIN3 = 1365, + SIM_GZ_EC_MIN4 = 1366, + SIM_GZ_EC_MIN5 = 1367, + SIM_GZ_EC_MIN6 = 1368, + SIM_GZ_EC_MIN7 = 1369, + SIM_GZ_EC_MIN8 = 1370, + SIM_GZ_EC_REV = 1371, + SIM_GZ_EN = 1372, + SIM_GZ_HOME_ALT = 1373, + SIM_GZ_HOME_LAT = 1374, + SIM_GZ_HOME_LON = 1375, + SIM_GZ_SV_DIS1 = 1376, + SIM_GZ_SV_DIS2 = 1377, + SIM_GZ_SV_DIS3 = 1378, + SIM_GZ_SV_DIS4 = 1379, + SIM_GZ_SV_DIS5 = 1380, + SIM_GZ_SV_DIS6 = 1381, + SIM_GZ_SV_DIS7 = 1382, + SIM_GZ_SV_DIS8 = 1383, + SIM_GZ_SV_FAIL1 = 1384, + SIM_GZ_SV_FAIL2 = 1385, + SIM_GZ_SV_FAIL3 = 1386, + SIM_GZ_SV_FAIL4 = 1387, + SIM_GZ_SV_FAIL5 = 1388, + SIM_GZ_SV_FAIL6 = 1389, + SIM_GZ_SV_FAIL7 = 1390, + SIM_GZ_SV_FAIL8 = 1391, + SIM_GZ_SV_FUNC1 = 1392, + SIM_GZ_SV_FUNC2 = 1393, + SIM_GZ_SV_FUNC3 = 1394, + SIM_GZ_SV_FUNC4 = 1395, + SIM_GZ_SV_FUNC5 = 1396, + SIM_GZ_SV_FUNC6 = 1397, + SIM_GZ_SV_FUNC7 = 1398, + SIM_GZ_SV_FUNC8 = 1399, + SIM_GZ_SV_MAX1 = 1400, + SIM_GZ_SV_MAX2 = 1401, + SIM_GZ_SV_MAX3 = 1402, + SIM_GZ_SV_MAX4 = 1403, + SIM_GZ_SV_MAX5 = 1404, + SIM_GZ_SV_MAX6 = 1405, + SIM_GZ_SV_MAX7 = 1406, + SIM_GZ_SV_MAX8 = 1407, + SIM_GZ_SV_MIN1 = 1408, + SIM_GZ_SV_MIN2 = 1409, + SIM_GZ_SV_MIN3 = 1410, + SIM_GZ_SV_MIN4 = 1411, + SIM_GZ_SV_MIN5 = 1412, + SIM_GZ_SV_MIN6 = 1413, + SIM_GZ_SV_MIN7 = 1414, + SIM_GZ_SV_MIN8 = 1415, + SIM_GZ_SV_REV = 1416, + SIM_MAG_OFFSET_X = 1417, + SIM_MAG_OFFSET_Y = 1418, + SIM_MAG_OFFSET_Z = 1419, + SYS_AUTOCONFIG = 1420, + SYS_AUTOSTART = 1421, + SYS_BL_UPDATE = 1422, + SYS_CAL_ACCEL = 1423, + SYS_CAL_BARO = 1424, + SYS_CAL_GYRO = 1425, + SYS_CAL_TDEL = 1426, + SYS_CAL_TMAX = 1427, + SYS_CAL_TMIN = 1428, + SYS_DM_BACKEND = 1429, + SYS_FAC_CAL_MODE = 1430, + SYS_FAILURE_EN = 1431, + SYS_HAS_BARO = 1432, + SYS_HAS_GPS = 1433, + SYS_HAS_MAG = 1434, + SYS_HAS_NUM_DIST = 1435, + SYS_HITL = 1436, + SYS_MC_EST_GROUP = 1437, + SYS_RGB_MAXBRT = 1438, + SYS_STCK_EN = 1439, + SYS_VEHICLE_RESP = 1440, + SYS_VEHICLE_TYPE = 1441, + TC_A0_ID = 1442, + TC_A0_TMAX = 1443, + TC_A0_TMIN = 1444, + TC_A0_TREF = 1445, + TC_A0_X0_0 = 1446, + TC_A0_X0_1 = 1447, + TC_A0_X0_2 = 1448, + TC_A0_X1_0 = 1449, + TC_A0_X1_1 = 1450, + TC_A0_X1_2 = 1451, + TC_A0_X2_0 = 1452, + TC_A0_X2_1 = 1453, + TC_A0_X2_2 = 1454, + TC_A0_X3_0 = 1455, + TC_A0_X3_1 = 1456, + TC_A0_X3_2 = 1457, + TC_A1_ID = 1458, + TC_A1_TMAX = 1459, + TC_A1_TMIN = 1460, + TC_A1_TREF = 1461, + TC_A1_X0_0 = 1462, + TC_A1_X0_1 = 1463, + TC_A1_X0_2 = 1464, + TC_A1_X1_0 = 1465, + TC_A1_X1_1 = 1466, + TC_A1_X1_2 = 1467, + TC_A1_X2_0 = 1468, + TC_A1_X2_1 = 1469, + TC_A1_X2_2 = 1470, + TC_A1_X3_0 = 1471, + TC_A1_X3_1 = 1472, + TC_A1_X3_2 = 1473, + TC_A2_ID = 1474, + TC_A2_TMAX = 1475, + TC_A2_TMIN = 1476, + TC_A2_TREF = 1477, + TC_A2_X0_0 = 1478, + TC_A2_X0_1 = 1479, + TC_A2_X0_2 = 1480, + TC_A2_X1_0 = 1481, + TC_A2_X1_1 = 1482, + TC_A2_X1_2 = 1483, + TC_A2_X2_0 = 1484, + TC_A2_X2_1 = 1485, + TC_A2_X2_2 = 1486, + TC_A2_X3_0 = 1487, + TC_A2_X3_1 = 1488, + TC_A2_X3_2 = 1489, + TC_A3_ID = 1490, + TC_A3_TMAX = 1491, + TC_A3_TMIN = 1492, + TC_A3_TREF = 1493, + TC_A3_X0_0 = 1494, + TC_A3_X0_1 = 1495, + TC_A3_X0_2 = 1496, + TC_A3_X1_0 = 1497, + TC_A3_X1_1 = 1498, + TC_A3_X1_2 = 1499, + TC_A3_X2_0 = 1500, + TC_A3_X2_1 = 1501, + TC_A3_X2_2 = 1502, + TC_A3_X3_0 = 1503, + TC_A3_X3_1 = 1504, + TC_A3_X3_2 = 1505, + TC_A_ENABLE = 1506, + TC_B0_ID = 1507, + TC_B0_TMAX = 1508, + TC_B0_TMIN = 1509, + TC_B0_TREF = 1510, + TC_B0_X0 = 1511, + TC_B0_X1 = 1512, + TC_B0_X2 = 1513, + TC_B0_X3 = 1514, + TC_B0_X4 = 1515, + TC_B0_X5 = 1516, + TC_B1_ID = 1517, + TC_B1_TMAX = 1518, + TC_B1_TMIN = 1519, + TC_B1_TREF = 1520, + TC_B1_X0 = 1521, + TC_B1_X1 = 1522, + TC_B1_X2 = 1523, + TC_B1_X3 = 1524, + TC_B1_X4 = 1525, + TC_B1_X5 = 1526, + TC_B2_ID = 1527, + TC_B2_TMAX = 1528, + TC_B2_TMIN = 1529, + TC_B2_TREF = 1530, + TC_B2_X0 = 1531, + TC_B2_X1 = 1532, + TC_B2_X2 = 1533, + TC_B2_X3 = 1534, + TC_B2_X4 = 1535, + TC_B2_X5 = 1536, + TC_B3_ID = 1537, + TC_B3_TMAX = 1538, + TC_B3_TMIN = 1539, + TC_B3_TREF = 1540, + TC_B3_X0 = 1541, + TC_B3_X1 = 1542, + TC_B3_X2 = 1543, + TC_B3_X3 = 1544, + TC_B3_X4 = 1545, + TC_B3_X5 = 1546, + TC_B_ENABLE = 1547, + TC_G0_ID = 1548, + TC_G0_TMAX = 1549, + TC_G0_TMIN = 1550, + TC_G0_TREF = 1551, + TC_G0_X0_0 = 1552, + TC_G0_X0_1 = 1553, + TC_G0_X0_2 = 1554, + TC_G0_X1_0 = 1555, + TC_G0_X1_1 = 1556, + TC_G0_X1_2 = 1557, + TC_G0_X2_0 = 1558, + TC_G0_X2_1 = 1559, + TC_G0_X2_2 = 1560, + TC_G0_X3_0 = 1561, + TC_G0_X3_1 = 1562, + TC_G0_X3_2 = 1563, + TC_G1_ID = 1564, + TC_G1_TMAX = 1565, + TC_G1_TMIN = 1566, + TC_G1_TREF = 1567, + TC_G1_X0_0 = 1568, + TC_G1_X0_1 = 1569, + TC_G1_X0_2 = 1570, + TC_G1_X1_0 = 1571, + TC_G1_X1_1 = 1572, + TC_G1_X1_2 = 1573, + TC_G1_X2_0 = 1574, + TC_G1_X2_1 = 1575, + TC_G1_X2_2 = 1576, + TC_G1_X3_0 = 1577, + TC_G1_X3_1 = 1578, + TC_G1_X3_2 = 1579, + TC_G2_ID = 1580, + TC_G2_TMAX = 1581, + TC_G2_TMIN = 1582, + TC_G2_TREF = 1583, + TC_G2_X0_0 = 1584, + TC_G2_X0_1 = 1585, + TC_G2_X0_2 = 1586, + TC_G2_X1_0 = 1587, + TC_G2_X1_1 = 1588, + TC_G2_X1_2 = 1589, + TC_G2_X2_0 = 1590, + TC_G2_X2_1 = 1591, + TC_G2_X2_2 = 1592, + TC_G2_X3_0 = 1593, + TC_G2_X3_1 = 1594, + TC_G2_X3_2 = 1595, + TC_G3_ID = 1596, + TC_G3_TMAX = 1597, + TC_G3_TMIN = 1598, + TC_G3_TREF = 1599, + TC_G3_X0_0 = 1600, + TC_G3_X0_1 = 1601, + TC_G3_X0_2 = 1602, + TC_G3_X1_0 = 1603, + TC_G3_X1_1 = 1604, + TC_G3_X1_2 = 1605, + TC_G3_X2_0 = 1606, + TC_G3_X2_1 = 1607, + TC_G3_X2_2 = 1608, + TC_G3_X3_0 = 1609, + TC_G3_X3_1 = 1610, + TC_G3_X3_2 = 1611, + TC_G_ENABLE = 1612, + TEST_D = 1613, + TEST_DEV = 1614, + TEST_D_LP = 1615, + TEST_HP = 1616, + TEST_I = 1617, + TEST_I_MAX = 1618, + TEST_LP = 1619, + TEST_MAX = 1620, + TEST_MEAN = 1621, + TEST_MIN = 1622, + TEST_P = 1623, + TEST_TRIM = 1624, + THR_MDL_FAC = 1625, + TRIG_ACT_TIME = 1626, + TRIG_DISTANCE = 1627, + TRIG_INTERFACE = 1628, + TRIG_INTERVAL = 1629, + TRIG_MIN_INTERVA = 1630, + TRIG_MODE = 1631, + TRIG_POLARITY = 1632, + TRIG_PWM_NEUTRAL = 1633, + TRIG_PWM_SHOOT = 1634, + TRIM_PITCH = 1635, + TRIM_ROLL = 1636, + TRIM_YAW = 1637, + UAVCAN_BITRATE = 1638, + UAVCAN_EC_FAIL1 = 1639, + UAVCAN_EC_FAIL2 = 1640, + UAVCAN_EC_FAIL3 = 1641, + UAVCAN_EC_FAIL4 = 1642, + UAVCAN_EC_FAIL5 = 1643, + UAVCAN_EC_FAIL6 = 1644, + UAVCAN_EC_FAIL7 = 1645, + UAVCAN_EC_FAIL8 = 1646, + UAVCAN_EC_FUNC1 = 1647, + UAVCAN_EC_FUNC2 = 1648, + UAVCAN_EC_FUNC3 = 1649, + UAVCAN_EC_FUNC4 = 1650, + UAVCAN_EC_FUNC5 = 1651, + UAVCAN_EC_FUNC6 = 1652, + UAVCAN_EC_FUNC7 = 1653, + UAVCAN_EC_FUNC8 = 1654, + UAVCAN_EC_MAX1 = 1655, + UAVCAN_EC_MAX2 = 1656, + UAVCAN_EC_MAX3 = 1657, + UAVCAN_EC_MAX4 = 1658, + UAVCAN_EC_MAX5 = 1659, + UAVCAN_EC_MAX6 = 1660, + UAVCAN_EC_MAX7 = 1661, + UAVCAN_EC_MAX8 = 1662, + UAVCAN_EC_MIN1 = 1663, + UAVCAN_EC_MIN2 = 1664, + UAVCAN_EC_MIN3 = 1665, + UAVCAN_EC_MIN4 = 1666, + UAVCAN_EC_MIN5 = 1667, + UAVCAN_EC_MIN6 = 1668, + UAVCAN_EC_MIN7 = 1669, + UAVCAN_EC_MIN8 = 1670, + UAVCAN_EC_REV = 1671, + UAVCAN_ENABLE = 1672, + UAVCAN_LGT_ANTCL = 1673, + UAVCAN_LGT_LAND = 1674, + UAVCAN_LGT_NAV = 1675, + UAVCAN_LGT_STROB = 1676, + UAVCAN_NODE_ID = 1677, + UAVCAN_PUB_ARM = 1678, + UAVCAN_PUB_MBD = 1679, + UAVCAN_PUB_RTCM = 1680, + UAVCAN_RNG_MAX = 1681, + UAVCAN_RNG_MIN = 1682, + UAVCAN_SUB_ASPD = 1683, + UAVCAN_SUB_BARO = 1684, + UAVCAN_SUB_BAT = 1685, + UAVCAN_SUB_BTN = 1686, + UAVCAN_SUB_DPRES = 1687, + UAVCAN_SUB_FLOW = 1688, + UAVCAN_SUB_GPS = 1689, + UAVCAN_SUB_HYGRO = 1690, + UAVCAN_SUB_ICE = 1691, + UAVCAN_SUB_IMU = 1692, + UAVCAN_SUB_MAG = 1693, + UAVCAN_SUB_RNG = 1694, + UAVCAN_SV_DIS1 = 1695, + UAVCAN_SV_DIS2 = 1696, + UAVCAN_SV_DIS3 = 1697, + UAVCAN_SV_DIS4 = 1698, + UAVCAN_SV_DIS5 = 1699, + UAVCAN_SV_DIS6 = 1700, + UAVCAN_SV_DIS7 = 1701, + UAVCAN_SV_DIS8 = 1702, + UAVCAN_SV_FAIL1 = 1703, + UAVCAN_SV_FAIL2 = 1704, + UAVCAN_SV_FAIL3 = 1705, + UAVCAN_SV_FAIL4 = 1706, + UAVCAN_SV_FAIL5 = 1707, + UAVCAN_SV_FAIL6 = 1708, + UAVCAN_SV_FAIL7 = 1709, + UAVCAN_SV_FAIL8 = 1710, + UAVCAN_SV_FUNC1 = 1711, + UAVCAN_SV_FUNC2 = 1712, + UAVCAN_SV_FUNC3 = 1713, + UAVCAN_SV_FUNC4 = 1714, + UAVCAN_SV_FUNC5 = 1715, + UAVCAN_SV_FUNC6 = 1716, + UAVCAN_SV_FUNC7 = 1717, + UAVCAN_SV_FUNC8 = 1718, + UAVCAN_SV_MAX1 = 1719, + UAVCAN_SV_MAX2 = 1720, + UAVCAN_SV_MAX3 = 1721, + UAVCAN_SV_MAX4 = 1722, + UAVCAN_SV_MAX5 = 1723, + UAVCAN_SV_MAX6 = 1724, + UAVCAN_SV_MAX7 = 1725, + UAVCAN_SV_MAX8 = 1726, + UAVCAN_SV_MIN1 = 1727, + UAVCAN_SV_MIN2 = 1728, + UAVCAN_SV_MIN3 = 1729, + UAVCAN_SV_MIN4 = 1730, + UAVCAN_SV_MIN5 = 1731, + UAVCAN_SV_MIN6 = 1732, + UAVCAN_SV_MIN7 = 1733, + UAVCAN_SV_MIN8 = 1734, + UAVCAN_SV_REV = 1735, + UXRCE_DDS_AG_IP = 1736, + UXRCE_DDS_DOM_ID = 1737, + UXRCE_DDS_KEY = 1738, + UXRCE_DDS_PRT = 1739, + VTO_LOITER_ALT = 1740, + VT_ARSP_BLEND = 1741, + VT_ARSP_TRANS = 1742, + VT_B_DEC_FF = 1743, + VT_B_DEC_I = 1744, + VT_B_DEC_MSS = 1745, + VT_B_TRANS_DUR = 1746, + VT_B_TRANS_RAMP = 1747, + VT_ELEV_MC_LOCK = 1748, + VT_FWD_THRUST_EN = 1749, + VT_FWD_THRUST_SC = 1750, + VT_FW_DIFTHR_EN = 1751, + VT_FW_DIFTHR_S_P = 1752, + VT_FW_DIFTHR_S_R = 1753, + VT_FW_DIFTHR_S_Y = 1754, + VT_FW_MIN_ALT = 1755, + VT_FW_QC_HMAX = 1756, + VT_FW_QC_P = 1757, + VT_FW_QC_R = 1758, + VT_F_TRANS_DUR = 1759, + VT_F_TRANS_THR = 1760, + VT_F_TR_OL_TM = 1761, + VT_LND_PITCH_MIN = 1762, + VT_PITCH_MIN = 1763, + VT_PSHER_SLEW = 1764, + VT_QC_ALT_LOSS = 1765, + VT_QC_T_ALT_LOSS = 1766, + VT_SPOILER_MC_LD = 1767, + VT_TILT_FW = 1768, + VT_TILT_MC = 1769, + VT_TILT_SPINUP = 1770, + VT_TILT_TRANS = 1771, + VT_TRANS_MIN_TM = 1772, + VT_TRANS_P2_DUR = 1773, + VT_TRANS_TIMEOUT = 1774, + VT_TYPE = 1775, + WEIGHT_BASE = 1776, + WEIGHT_GROSS = 1777, + WV_EN = 1778, + WV_GAIN = 1779, + WV_ROLL_MIN = 1780, + WV_YRATE_MAX = 1781, }; static constexpr param_info_s params_meta[] = { @@ -7180,6 +7194,12 @@ static constexpr param_info_s params_meta[] = { .value = { .i32 = 1}, .flag = { .value = 0 }, }, + { + .name = "MAV_0_BROADCAST", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 1}, + .flag = { .value = 0 }, + }, { .name = "MAV_0_CONFIG", .type = PARAM_TYPE_INT32, @@ -7216,6 +7236,30 @@ static constexpr param_info_s params_meta[] = { .value = { .i32 = 1200}, .flag = { .value = 0 }, }, + { + .name = "MAV_0_REMOTE_IP", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, + { + .name = "MAV_0_REMOTE_PRT", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 14550}, + .flag = { .value = 0 }, + }, + { + .name = "MAV_0_UDP_PRT", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 14556}, + .flag = { .value = 0 }, + }, + { + .name = "MAV_1_BROADCAST", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, { .name = "MAV_1_CONFIG", .type = PARAM_TYPE_INT32, @@ -7252,6 +7296,30 @@ static constexpr param_info_s params_meta[] = { .value = { .i32 = 0}, .flag = { .value = 0 }, }, + { + .name = "MAV_1_REMOTE_IP", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, + { + .name = "MAV_1_REMOTE_PRT", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, + { + .name = "MAV_1_UDP_PRT", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, + { + .name = "MAV_2_BROADCAST", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, { .name = "MAV_2_CONFIG", .type = PARAM_TYPE_INT32, @@ -7288,6 +7356,24 @@ static constexpr param_info_s params_meta[] = { .value = { .i32 = 0}, .flag = { .value = 0 }, }, + { + .name = "MAV_2_REMOTE_IP", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, + { + .name = "MAV_2_REMOTE_PRT", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, + { + .name = "MAV_2_UDP_PRT", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 0}, + .flag = { .value = 0 }, + }, { .name = "MAV_COMP_ID", .type = PARAM_TYPE_INT32, @@ -12136,6 +12222,12 @@ static constexpr param_info_s params_meta[] = { .value = { .i32 = 0}, .flag = { .value = 0 }, }, + { + .name = "UXRCE_DDS_AG_IP", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 2130706433}, + .flag = { .value = 0 }, + }, { .name = "UXRCE_DDS_DOM_ID", .type = PARAM_TYPE_INT32, @@ -12148,6 +12240,12 @@ static constexpr param_info_s params_meta[] = { .value = { .i32 = 1}, .flag = { .value = 0 }, }, + { + .name = "UXRCE_DDS_PRT", + .type = PARAM_TYPE_INT32, + .value = { .i32 = 8888}, + .flag = { .value = 0 }, + }, { .name = "VTO_LOITER_ALT", .type = PARAM_TYPE_FLOAT, @@ -13330,6 +13428,18 @@ static constexpr param_type_t params_type[] = { PARAM_TYPE_INT32, PARAM_TYPE_INT32, PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, PARAM_TYPE_FLOAT, PARAM_TYPE_FLOAT, PARAM_TYPE_FLOAT, @@ -14129,6 +14239,8 @@ static constexpr param_type_t params_type[] = { PARAM_TYPE_INT32, PARAM_TYPE_INT32, PARAM_TYPE_INT32, + PARAM_TYPE_INT32, + PARAM_TYPE_INT32, PARAM_TYPE_FLOAT, PARAM_TYPE_FLOAT, PARAM_TYPE_FLOAT, diff --git a/pkgs/param/module_params.c b/pkgs/param/module_params.c index b918eb6c9e..f8d016e899 100644 --- a/pkgs/param/module_params.c +++ b/pkgs/param/module_params.c @@ -1,1329 +1,1836 @@ /** - * uXRCE-DDS domain ID - * - * uXRCE-DDS domain ID - * - * @group UXRCE-DDS Client - * @category System - * @reboot_required True - */ -PARAM_DEFINE_INT32(UXRCE_DDS_DOM_ID, 0); - -/** - * uXRCE-DDS Session key + * UAVCAN ESC 1 Output Function * - * uXRCE-DDS key, must be different from zero. - * In a single agent - multi client configuration, each client - * must have a unique session key. + * Select what should be output on UAVCAN ESC 1. * - * - * @group UXRCE-DDS Client - * @category System - * @reboot_required True - */ -PARAM_DEFINE_INT32(UXRCE_DDS_KEY, 1); - -/** - * 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. + * 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 8 - * @reboot_required True + * @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(BAT1_V_DIV, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC1, 0); /** - * Battery 2 voltage divider (V divider) + * UAVCAN ESC 2 Output Function * - * 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. + * Select what should be output on UAVCAN ESC 2. * - * - * @group Battery Calibration - * @decimal 8 - * @reboot_required True - */ -PARAM_DEFINE_FLOAT(BAT2_V_DIV, -1.0); - -/** - * 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. + * 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 8 - * @reboot_required True + * @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(BAT1_A_PER_V, -1.0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC2, 0); /** - * Battery 2 current per volt (A/V) + * UAVCAN ESC 3 Output Function * - * 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. + * Select what should be output on UAVCAN ESC 3. * - * - * @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. + * 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 - * @reboot_required True + * @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(BAT1_V_CHANNEL, -1); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC3, 0); /** - * Battery 2 Voltage ADC Channel + * UAVCAN ESC 4 Output Function * - * This parameter specifies the ADC channel used to monitor voltage of main power battery. - * A value of -1 means to use the board default. + * Select what should be output on UAVCAN ESC 4. * - * - * @group Battery Calibration - * @reboot_required True - */ -PARAM_DEFINE_INT32(BAT2_V_CHANNEL, -1); - -/** - * 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. + * 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 - * @reboot_required True + * @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(BAT1_I_CHANNEL, -1); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC4, 0); /** - * Battery 2 Current ADC Channel + * UAVCAN ESC 5 Output Function * - * This parameter specifies the ADC channel used to monitor current of main power battery. - * A value of -1 means to use the board default. + * Select what should be output on UAVCAN ESC 5. * - * - * @group Battery Calibration - * @reboot_required True - */ -PARAM_DEFINE_INT32(BAT2_I_CHANNEL, -1); - -/** - * MAVLink Config for instance 0 - * - * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance + * 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 MAVLink + * @group Actuator Outputs * @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 + * @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(MAV_0_CONFIG, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC5, 0); /** - * MAVLink Config for instance 1 + * UAVCAN ESC 6 Output Function * - * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance + * Select what should be output on UAVCAN ESC 6. * - * - * @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 + * 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 MAVLink + * @group Actuator Outputs * @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 + * @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(MAV_2_CONFIG, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC6, 0); /** - * MAVLink Mode for instance 0 + * UAVCAN ESC 7 Output Function * - * The MAVLink Mode defines the set of streamed messages (for example the - * vehicle's attitude) and their sending rates. + * 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 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 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(MAV_0_MODE, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC7, 0); /** - * MAVLink Mode for instance 1 + * UAVCAN ESC 8 Output Function * - * The MAVLink Mode defines the set of streamed messages (for example the - * vehicle's attitude) and their sending rates. + * 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 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 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(MAV_1_MODE, 2); +PARAM_DEFINE_INT32(UAVCAN_EC_FUNC8, 0); /** - * MAVLink Mode for instance 2 + * UAVCAN ESC 1 Minimum Value * - * The MAVLink Mode defines the set of streamed messages (for example the - * vehicle's attitude) and their sending rates. + * Minimum output value (when not disarmed). * * - * @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 Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_2_MODE, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN1, 1); /** - * Maximum MAVLink sending rate for instance 0 + * UAVCAN ESC 2 Minimum Value * - * 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). + * Minimum output value (when not disarmed). * * - * @group MAVLink + * @group Actuator Outputs * @min 0 - * @unit B/s - * @reboot_required True + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_0_RATE, 1200); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN2, 1); /** - * Maximum MAVLink sending rate for instance 1 + * UAVCAN ESC 3 Minimum Value * - * 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). + * Minimum output value (when not disarmed). * * - * @group MAVLink + * @group Actuator Outputs * @min 0 - * @unit B/s - * @reboot_required True + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_1_RATE, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN3, 1); /** - * Maximum MAVLink sending rate for instance 2 + * UAVCAN ESC 4 Minimum Value * - * 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). + * Minimum output value (when not disarmed). * * - * @group MAVLink + * @group Actuator Outputs * @min 0 - * @unit B/s - * @reboot_required True + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_2_RATE, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN4, 1); /** - * Enable MAVLink Message forwarding for instance 0 + * UAVCAN ESC 5 Minimum Value * - * 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). + * Minimum output value (when not disarmed). * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_0_FORWARD, 1); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN5, 1); /** - * Enable MAVLink Message forwarding for instance 1 + * UAVCAN ESC 6 Minimum Value * - * 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). + * Minimum output value (when not disarmed). * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_1_FORWARD, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN6, 1); /** - * Enable MAVLink Message forwarding for instance 2 + * UAVCAN ESC 7 Minimum Value * - * 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). + * Minimum output value (when not disarmed). * * - * @group MAVLink - * @boolean - * @reboot_required True - */ -PARAM_DEFINE_INT32(MAV_2_FORWARD, 0); + * @group Actuator Outputs + * @min 0 + * @max 8191 + */ +PARAM_DEFINE_INT32(UAVCAN_EC_MIN7, 1); /** - * Enable software throttling of mavlink on instance 0 + * UAVCAN ESC 8 Minimum Value * - * 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. + * Minimum output value (when not disarmed). * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_0_RADIO_CTL, 1); +PARAM_DEFINE_INT32(UAVCAN_EC_MIN8, 1); /** - * Enable software throttling of mavlink on instance 1 + * UAVCAN ESC 1 Maximum Value * - * 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. + * Maxmimum output value (when not disarmed). * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_1_RADIO_CTL, 1); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX1, 8191); /** - * Enable software throttling of mavlink on instance 2 + * UAVCAN ESC 2 Maximum Value * - * If enabled, MAVLink messages will be throttled according to - * `txbuf` field reported by radio_status. + * Maxmimum output value (when not disarmed). * - * Requires a radio to send the mavlink message RADIO_STATUS. + * + * @group Actuator Outputs + * @min 0 + * @max 8191 + */ +PARAM_DEFINE_INT32(UAVCAN_EC_MAX2, 8191); + +/** + * UAVCAN ESC 3 Maximum Value + * + * Maxmimum output value (when not disarmed). * * - * @group MAVLink - * @boolean - * @reboot_required True + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_2_RADIO_CTL, 1); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX3, 8191); /** - * Enable serial flow control for instance 0 + * UAVCAN ESC 4 Maximum Value * - * 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. + * Maxmimum output value (when not disarmed). * * - * @group MAVLink - * @value 0 Force off - * @value 1 Force on - * @value 2 Auto-detected - * @reboot_required True + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_0_FLOW_CTRL, 2); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX4, 8191); /** - * Enable serial flow control for instance 1 + * UAVCAN ESC 5 Maximum Value * - * 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. + * Maxmimum output value (when not disarmed). * * - * @group MAVLink - * @value 0 Force off - * @value 1 Force on - * @value 2 Auto-detected - * @reboot_required True + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_1_FLOW_CTRL, 2); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX5, 8191); /** - * Enable serial flow control for instance 2 + * UAVCAN ESC 6 Maximum Value * - * 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. + * Maxmimum output value (when not disarmed). * * - * @group MAVLink - * @value 0 Force off - * @value 1 Force on - * @value 2 Auto-detected - * @reboot_required True + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(MAV_2_FLOW_CTRL, 2); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX6, 8191); /** - * Accelerometer 0 calibration device ID + * UAVCAN ESC 7 Maximum Value * - * Device ID of the accelerometer this calibration applies to. + * Maxmimum output value (when not disarmed). + * * - * @group Sensor Calibration - * @decimal 3 - * @category System + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC0_ID, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX7, 8191); /** - * Accelerometer 1 calibration device ID + * UAVCAN ESC 8 Maximum Value * - * Device ID of the accelerometer this calibration applies to. + * Maxmimum output value (when not disarmed). + * * - * @group Sensor Calibration - * @decimal 3 - * @category System + * @group Actuator Outputs + * @min 0 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC1_ID, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_MAX8, 8191); /** - * Accelerometer 2 calibration device ID + * UAVCAN ESC 1 Failsafe Value * - * Device ID of the accelerometer this calibration applies to. + * 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 Sensor Calibration - * @decimal 3 - * @category System + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC2_ID, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL1, -1); /** - * Accelerometer 3 calibration device ID + * UAVCAN ESC 2 Failsafe Value * - * Device ID of the accelerometer this calibration applies to. + * 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 Sensor Calibration - * @decimal 3 - * @category System + * @group Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC3_ID, 0); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL2, -1); /** - * Accelerometer 0 priority + * UAVCAN 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). * * - * @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 Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC0_PRIO, -1); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL3, -1); /** - * Accelerometer 1 priority + * UAVCAN 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). * * - * @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 Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC1_PRIO, -1); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL4, -1); /** - * Accelerometer 2 priority + * UAVCAN 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). * * - * @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 Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC2_PRIO, -1); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL5, -1); /** - * Accelerometer 3 priority + * UAVCAN 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). * * - * @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 Actuator Outputs + * @min -1 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC3_PRIO, -1); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL6, -1); /** - * Accelerometer 0 rotation relative to airframe + * UAVCAN ESC 7 Failsafe Value * - * 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. + * 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 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 + * @group Actuator Outputs * @min -1 - * @max 40 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC0_ROT, -1); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL7, -1); /** - * Accelerometer 1 rotation relative to airframe + * UAVCAN ESC 8 Failsafe Value * - * 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. + * 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 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 + * @group Actuator Outputs * @min -1 - * @max 40 + * @max 8191 */ -PARAM_DEFINE_INT32(CAL_ACC1_ROT, -1); +PARAM_DEFINE_INT32(UAVCAN_EC_FAIL8, -1); /** - * Accelerometer 2 rotation relative to airframe + * UAVCAN Servo 1 Output Function * - * 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. + * 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 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 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(CAL_ACC2_ROT, -1); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC1, 0); /** - * Accelerometer 3 rotation relative to airframe + * UAVCAN Servo 2 Output Function * - * 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. + * 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 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 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(CAL_ACC3_ROT, -1); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC2, 0); /** - * Accelerometer 0 X-axis offset + * UAVCAN Servo 3 Output Function * + * 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @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(CAL_ACC0_XOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC3, 0); /** - * Accelerometer 1 X-axis offset + * UAVCAN Servo 4 Output Function * + * 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @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(CAL_ACC1_XOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC4, 0); /** - * Accelerometer 2 X-axis offset + * UAVCAN Servo 5 Output Function * + * 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @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(CAL_ACC2_XOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC5, 0); /** - * Accelerometer 3 X-axis offset + * UAVCAN Servo 6 Output Function * + * Select what should be output on UAVCAN Servo 6. * - * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^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 + * @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(CAL_ACC3_XOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC6, 0); /** - * Accelerometer 0 Y-axis offset + * UAVCAN Servo 7 Output Function * + * Select what should be output on UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @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(CAL_ACC0_YOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC7, 0); /** - * Accelerometer 1 Y-axis offset + * UAVCAN Servo 8 Output Function * + * Select what should be output on UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @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(CAL_ACC1_YOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FUNC8, 0); /** - * Accelerometer 2 Y-axis offset + * UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_YOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS1, 500); /** - * Accelerometer 3 Y-axis offset + * UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_YOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS2, 500); /** - * Accelerometer 0 Z-axis offset + * UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_ZOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS3, 500); /** - * Accelerometer 1 Z-axis offset + * UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_ZOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS4, 500); /** - * Accelerometer 2 Z-axis offset + * UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_ZOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS5, 500); /** - * Accelerometer 3 Z-axis offset + * UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @unit m/s^2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_ZOFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS6, 500); /** - * Accelerometer 0 X-axis scaling factor + * UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_XSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS7, 500); /** - * Accelerometer 1 X-axis scaling factor + * UAVCAN 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 Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_XSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_DIS8, 500); /** - * Accelerometer 2 X-axis scaling factor + * UAVCAN Servo 1 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_XSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN1, 0); /** - * Accelerometer 3 X-axis scaling factor + * UAVCAN Servo 2 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_XSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN2, 0); /** - * Accelerometer 0 Y-axis scaling factor + * UAVCAN Servo 3 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_YSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN3, 0); /** - * Accelerometer 1 Y-axis scaling factor + * UAVCAN Servo 4 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_YSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN4, 0); /** - * Accelerometer 2 Y-axis scaling factor + * UAVCAN Servo 5 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_YSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN5, 0); /** - * Accelerometer 3 Y-axis scaling factor + * UAVCAN Servo 6 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_YSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN6, 0); /** - * Accelerometer 0 Z-axis scaling factor + * UAVCAN Servo 7 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC0_ZSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN7, 0); /** - * Accelerometer 1 Z-axis scaling factor + * UAVCAN Servo 8 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC1_ZSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MIN8, 0); /** - * Accelerometer 2 Z-axis scaling factor + * UAVCAN Servo 1 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC2_ZSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX1, 1000); /** - * Accelerometer 3 Z-axis scaling factor + * UAVCAN Servo 2 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_ACC3_ZSCALE, 1.0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX2, 1000); /** - * Barometer 0 calibration device ID + * UAVCAN Servo 3 Maximum Value * - * Device ID of the barometer this calibration applies to. + * Maxmimum output value (when not disarmed). + * * - * @group Sensor Calibration - * @category System + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CAL_BARO0_ID, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX3, 1000); /** - * Barometer 1 calibration device ID + * UAVCAN Servo 4 Maximum Value * - * Device ID of the barometer this calibration applies to. + * Maxmimum output value (when not disarmed). + * * - * @group Sensor Calibration - * @category System + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CAL_BARO1_ID, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX4, 1000); /** - * Barometer 2 calibration device ID + * UAVCAN Servo 5 Maximum Value * - * Device ID of the barometer this calibration applies to. + * Maxmimum output value (when not disarmed). + * * - * @group Sensor Calibration - * @category System + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CAL_BARO2_ID, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX5, 1000); /** - * Barometer 3 calibration device ID + * UAVCAN Servo 6 Maximum Value * - * Device ID of the barometer this calibration applies to. + * Maxmimum output value (when not disarmed). + * * - * @group Sensor Calibration - * @category System + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CAL_BARO3_ID, 0); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX6, 1000); /** - * Barometer 0 priority + * UAVCAN Servo 7 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @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(CAL_BARO0_PRIO, -1); + * @group Actuator Outputs + * @min 0 + * @max 1000 + */ +PARAM_DEFINE_INT32(UAVCAN_SV_MAX7, 1000); /** - * Barometer 1 priority + * UAVCAN Servo 8 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @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 Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CAL_BARO1_PRIO, -1); +PARAM_DEFINE_INT32(UAVCAN_SV_MAX8, 1000); /** - * Barometer 2 priority + * UAVCAN 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). * * - * @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 Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CAL_BARO2_PRIO, -1); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL1, -1); /** - * Barometer 3 priority + * UAVCAN 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). * * - * @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 Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CAL_BARO3_PRIO, -1); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL2, -1); /** - * Barometer 0 offset + * UAVCAN 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). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_BARO0_OFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL3, -1); /** - * Barometer 1 offset + * UAVCAN 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). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_BARO1_OFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL4, -1); /** - * Barometer 2 offset + * UAVCAN 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). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_BARO2_OFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL5, -1); /** - * Barometer 3 offset + * UAVCAN 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). * * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CAL_BARO3_OFF, 0.0); +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL6, -1); /** - * Gyroscope 0 calibration device ID + * UAVCAN Servo 7 Failsafe Value * - * Device ID of the gyroscope this calibration applies to. + * 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 Actuator Outputs + * @min -1 + * @max 1000 + */ +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL7, -1); + +/** + * 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 Actuator Outputs + * @min -1 + * @max 1000 + */ +PARAM_DEFINE_INT32(UAVCAN_SV_FAIL8, -1); + +/** + * Reverse Output Range for UAVCAN + * + * 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 + * @min 0 + * @max 255 + */ +PARAM_DEFINE_INT32(UAVCAN_EC_REV, 0); + +/** + * Reverse Output Range for UAVCAN + * + * 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 + * @min 0 + * @max 255 + */ +PARAM_DEFINE_INT32(UAVCAN_SV_REV, 0); + +/** + * Accelerometer 0 calibration device ID + * + * Device ID of the accelerometer this calibration applies to. * * @group Sensor Calibration + * @decimal 3 * @category System */ -PARAM_DEFINE_INT32(CAL_GYRO0_ID, 0); +PARAM_DEFINE_INT32(CAL_ACC0_ID, 0); /** - * Gyroscope 1 calibration device ID + * Accelerometer 1 calibration device ID * - * Device ID of the gyroscope this calibration applies to. + * Device ID of the accelerometer this calibration applies to. * * @group Sensor Calibration + * @decimal 3 * @category System */ -PARAM_DEFINE_INT32(CAL_GYRO1_ID, 0); +PARAM_DEFINE_INT32(CAL_ACC1_ID, 0); /** - * Gyroscope 2 calibration device ID + * Accelerometer 2 calibration device ID * - * Device ID of the gyroscope this calibration applies to. + * Device ID of the accelerometer this calibration applies to. * * @group Sensor Calibration + * @decimal 3 * @category System */ -PARAM_DEFINE_INT32(CAL_GYRO2_ID, 0); +PARAM_DEFINE_INT32(CAL_ACC2_ID, 0); /** - * Gyroscope 3 calibration device ID + * Accelerometer 3 calibration device ID * - * Device ID of the gyroscope this calibration applies to. + * Device ID of the accelerometer this calibration applies to. * * @group Sensor Calibration + * @decimal 3 * @category System */ -PARAM_DEFINE_INT32(CAL_GYRO3_ID, 0); +PARAM_DEFINE_INT32(CAL_ACC3_ID, 0); /** - * Gyroscope 0 priority + * Accelerometer 0 priority * * * @@ -1335,12 +1842,13 @@ PARAM_DEFINE_INT32(CAL_GYRO3_ID, 0); * @value 50 Medium (Default) * @value 75 High * @value 100 Max + * @decimal 3 * @category System */ -PARAM_DEFINE_INT32(CAL_GYRO0_PRIO, -1); +PARAM_DEFINE_INT32(CAL_ACC0_PRIO, -1); /** - * Gyroscope 1 priority + * Accelerometer 1 priority * * * @@ -1352,12 +1860,13 @@ PARAM_DEFINE_INT32(CAL_GYRO0_PRIO, -1); * @value 50 Medium (Default) * @value 75 High * @value 100 Max + * @decimal 3 * @category System */ -PARAM_DEFINE_INT32(CAL_GYRO1_PRIO, -1); +PARAM_DEFINE_INT32(CAL_ACC1_PRIO, -1); /** - * Gyroscope 2 priority + * Accelerometer 2 priority * * * @@ -1369,12 +1878,13 @@ PARAM_DEFINE_INT32(CAL_GYRO1_PRIO, -1); * @value 50 Medium (Default) * @value 75 High * @value 100 Max + * @decimal 3 * @category System */ -PARAM_DEFINE_INT32(CAL_GYRO2_PRIO, -1); +PARAM_DEFINE_INT32(CAL_ACC2_PRIO, -1); /** - * Gyroscope 3 priority + * Accelerometer 3 priority * * * @@ -1386,12 +1896,13 @@ PARAM_DEFINE_INT32(CAL_GYRO2_PRIO, -1); * @value 50 Medium (Default) * @value 75 High * @value 100 Max + * @decimal 3 * @category System */ -PARAM_DEFINE_INT32(CAL_GYRO3_PRIO, -1); +PARAM_DEFINE_INT32(CAL_ACC3_PRIO, -1); /** - * Gyroscope 0 rotation relative to airframe + * Accelerometer 0 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. * @@ -1443,10 +1954,10 @@ PARAM_DEFINE_INT32(CAL_GYRO3_PRIO, -1); * @min -1 * @max 40 */ -PARAM_DEFINE_INT32(CAL_GYRO0_ROT, -1); +PARAM_DEFINE_INT32(CAL_ACC0_ROT, -1); /** - * Gyroscope 1 rotation relative to airframe + * Accelerometer 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. * @@ -1498,10 +2009,10 @@ PARAM_DEFINE_INT32(CAL_GYRO0_ROT, -1); * @min -1 * @max 40 */ -PARAM_DEFINE_INT32(CAL_GYRO1_ROT, -1); +PARAM_DEFINE_INT32(CAL_ACC1_ROT, -1); /** - * Gyroscope 2 rotation relative to airframe + * 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. * @@ -1553,10 +2064,10 @@ PARAM_DEFINE_INT32(CAL_GYRO1_ROT, -1); * @min -1 * @max 40 */ -PARAM_DEFINE_INT32(CAL_GYRO2_ROT, -1); +PARAM_DEFINE_INT32(CAL_ACC2_ROT, -1); /** - * Gyroscope 3 rotation relative to airframe + * Accelerometer 3 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. * @@ -1608,10 +2119,10 @@ PARAM_DEFINE_INT32(CAL_GYRO2_ROT, -1); * @min -1 * @max 40 */ -PARAM_DEFINE_INT32(CAL_GYRO3_ROT, -1); +PARAM_DEFINE_INT32(CAL_ACC3_ROT, -1); /** - * Gyroscope 0 X-axis offset + * Accelerometer 0 X-axis offset * * * @@ -1619,12 +2130,12 @@ PARAM_DEFINE_INT32(CAL_GYRO3_ROT, -1); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO0_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC0_XOFF, 0.0); /** - * Gyroscope 1 X-axis offset + * Accelerometer 1 X-axis offset * * * @@ -1632,12 +2143,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO0_XOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO1_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC1_XOFF, 0.0); /** - * Gyroscope 2 X-axis offset + * Accelerometer 2 X-axis offset * * * @@ -1645,12 +2156,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO1_XOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO2_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC2_XOFF, 0.0); /** - * Gyroscope 3 X-axis offset + * Accelerometer 3 X-axis offset * * * @@ -1658,12 +2169,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO2_XOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO3_XOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC3_XOFF, 0.0); /** - * Gyroscope 0 Y-axis offset + * Accelerometer 0 Y-axis offset * * * @@ -1671,12 +2182,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO3_XOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC0_YOFF, 0.0); /** - * Gyroscope 1 Y-axis offset + * Accelerometer 1 Y-axis offset * * * @@ -1684,12 +2195,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC1_YOFF, 0.0); /** - * Gyroscope 2 Y-axis offset + * Accelerometer 2 Y-axis offset * * * @@ -1697,12 +2208,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC2_YOFF, 0.0); /** - * Gyroscope 3 Y-axis offset + * Accelerometer 3 Y-axis offset * * * @@ -1710,12 +2221,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO3_YOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC3_YOFF, 0.0); /** - * Gyroscope 0 Z-axis offset + * Accelerometer 0 Z-axis offset * * * @@ -1723,12 +2234,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO3_YOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC0_ZOFF, 0.0); /** - * Gyroscope 1 Z-axis offset + * Accelerometer 1 Z-axis offset * * * @@ -1736,12 +2247,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC1_ZOFF, 0.0); /** - * Gyroscope 2 Z-axis offset + * Accelerometer 2 Z-axis offset * * * @@ -1749,12 +2260,12 @@ PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC2_ZOFF, 0.0); /** - * Gyroscope 3 Z-axis offset + * Accelerometer 3 Z-axis offset * * * @@ -1762,444 +2273,288 @@ PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit rad/s + * @unit m/s^2 */ -PARAM_DEFINE_FLOAT(CAL_GYRO3_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_ACC3_ZOFF, 0.0); /** - * Magnetometer 0 calibration device ID + * Accelerometer 0 X-axis scaling factor * - * Device ID of the magnetometer this calibration applies to. + * * * @group Sensor Calibration + * @decimal 3 * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG0_ID, 0); +PARAM_DEFINE_FLOAT(CAL_ACC0_XSCALE, 1.0); /** - * Magnetometer 1 calibration device ID + * Accelerometer 1 X-axis scaling factor * - * Device ID of the magnetometer this calibration applies to. + * * * @group Sensor Calibration + * @decimal 3 * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG1_ID, 0); +PARAM_DEFINE_FLOAT(CAL_ACC1_XSCALE, 1.0); /** - * Magnetometer 2 calibration device ID + * Accelerometer 2 X-axis scaling factor * - * Device ID of the magnetometer this calibration applies to. + * * * @group Sensor Calibration + * @decimal 3 * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG2_ID, 0); +PARAM_DEFINE_FLOAT(CAL_ACC2_XSCALE, 1.0); /** - * Magnetometer 3 calibration device ID + * Accelerometer 3 X-axis scaling factor * - * Device ID of the magnetometer this calibration applies to. + * * * @group Sensor Calibration + * @decimal 3 * @category System + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG3_ID, 0); +PARAM_DEFINE_FLOAT(CAL_ACC3_XSCALE, 1.0); /** - * Magnetometer 0 priority + * Accelerometer 0 Y-axis scaling factor * * * * @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 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG0_PRIO, -1); +PARAM_DEFINE_FLOAT(CAL_ACC0_YSCALE, 1.0); /** - * Magnetometer 1 priority + * Accelerometer 1 Y-axis scaling factor * * * * @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 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG1_PRIO, -1); +PARAM_DEFINE_FLOAT(CAL_ACC1_YSCALE, 1.0); /** - * Magnetometer 2 priority + * Accelerometer 2 Y-axis scaling factor * * * * @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 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG2_PRIO, -1); +PARAM_DEFINE_FLOAT(CAL_ACC2_YSCALE, 1.0); /** - * Magnetometer 3 priority + * Accelerometer 3 Y-axis scaling factor * * * * @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 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG3_PRIO, -1); +PARAM_DEFINE_FLOAT(CAL_ACC3_YSCALE, 1.0); /** - * Magnetometer 0 rotation relative to airframe + * Accelerometer 0 Z-axis scaling factor * - * 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° + * @decimal 3 * @category System - * @min -1 - * @max 40 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG0_ROT, -1); +PARAM_DEFINE_FLOAT(CAL_ACC0_ZSCALE, 1.0); /** - * Magnetometer 1 rotation relative to airframe + * Accelerometer 1 Z-axis scaling factor * - * 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° + * @decimal 3 * @category System - * @min -1 - * @max 40 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG1_ROT, -1); +PARAM_DEFINE_FLOAT(CAL_ACC1_ZSCALE, 1.0); /** - * Magnetometer 2 rotation relative to airframe + * Accelerometer 2 Z-axis scaling factor * - * 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° + * @decimal 3 * @category System - * @min -1 - * @max 40 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG2_ROT, -1); +PARAM_DEFINE_FLOAT(CAL_ACC2_ZSCALE, 1.0); /** - * Magnetometer 3 rotation relative to airframe + * Accelerometer 3 Z-axis scaling factor * - * 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° + * @decimal 3 * @category System - * @min -1 - * @max 40 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(CAL_MAG3_ROT, -1); +PARAM_DEFINE_FLOAT(CAL_ACC3_ZSCALE, 1.0); /** - * Magnetometer 0 X-axis offset + * Barometer 0 calibration device ID * - * + * Device ID of the barometer this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG0_XOFF, 0.0); +PARAM_DEFINE_INT32(CAL_BARO0_ID, 0); /** - * Magnetometer 1 X-axis offset + * Barometer 1 calibration device ID * - * + * Device ID of the barometer this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG1_XOFF, 0.0); +PARAM_DEFINE_INT32(CAL_BARO1_ID, 0); /** - * Magnetometer 2 X-axis offset + * Barometer 2 calibration device ID * - * + * Device ID of the barometer this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG2_XOFF, 0.0); +PARAM_DEFINE_INT32(CAL_BARO2_ID, 0); /** - * Magnetometer 3 X-axis offset + * Barometer 3 calibration device ID * - * + * Device ID of the barometer this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG3_XOFF, 0.0); +PARAM_DEFINE_INT32(CAL_BARO3_ID, 0); /** - * Magnetometer 0 Y-axis offset + * Barometer 0 priority * * * * @group Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG0_YOFF, 0.0); +PARAM_DEFINE_INT32(CAL_BARO0_PRIO, -1); /** - * Magnetometer 1 Y-axis offset + * Barometer 1 priority * * * * @group Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG1_YOFF, 0.0); +PARAM_DEFINE_INT32(CAL_BARO1_PRIO, -1); /** - * Magnetometer 2 Y-axis offset + * Barometer 2 priority * * * * @group Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG2_YOFF, 0.0); +PARAM_DEFINE_INT32(CAL_BARO2_PRIO, -1); /** - * Magnetometer 3 Y-axis offset + * Barometer 3 priority * * * * @group Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG3_YOFF, 0.0); +PARAM_DEFINE_INT32(CAL_BARO3_PRIO, -1); /** - * Magnetometer 0 Z-axis offset + * Barometer 0 offset * * * @@ -2207,12 +2562,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG3_YOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG0_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_BARO0_OFF, 0.0); /** - * Magnetometer 1 Z-axis offset + * Barometer 1 offset * * * @@ -2220,12 +2574,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG0_ZOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG1_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_BARO1_OFF, 0.0); /** - * Magnetometer 2 Z-axis offset + * Barometer 2 offset * * * @@ -2233,12 +2586,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG1_ZOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG2_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_BARO2_OFF, 0.0); /** - * Magnetometer 3 Z-axis offset + * Barometer 3 offset * * * @@ -2246,192 +2598,339 @@ PARAM_DEFINE_FLOAT(CAL_MAG2_ZOFF, 0.0); * @decimal 3 * @category System * @volatile True - * @unit gauss */ -PARAM_DEFINE_FLOAT(CAL_MAG3_ZOFF, 0.0); +PARAM_DEFINE_FLOAT(CAL_BARO3_OFF, 0.0); /** - * Magnetometer 0 X-axis scaling factor + * Gyroscope 0 calibration device ID * - * + * Device ID of the gyroscope this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True - * @min 0.1 - * @max 3.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_XSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO0_ID, 0); /** - * Magnetometer 1 X-axis scaling factor + * Gyroscope 1 calibration device ID * - * + * Device ID of the gyroscope this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True - * @min 0.1 - * @max 3.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_XSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO1_ID, 0); /** - * Magnetometer 2 X-axis scaling factor - * - * - * - * @group Sensor Calibration - * @decimal 3 - * @category System - * @volatile True - * @min 0.1 - * @max 3.0 - */ -PARAM_DEFINE_FLOAT(CAL_MAG2_XSCALE, 1.0); - -/** - * Magnetometer 3 X-axis scaling factor + * Gyroscope 2 calibration device ID * - * + * Device ID of the gyroscope this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True - * @min 0.1 - * @max 3.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_XSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO2_ID, 0); /** - * Magnetometer 0 Y-axis scaling factor + * Gyroscope 3 calibration device ID * - * + * Device ID of the gyroscope this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True - * @min 0.1 - * @max 3.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_YSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO3_ID, 0); /** - * Magnetometer 1 Y-axis scaling factor + * Gyroscope 0 priority * * * * @group Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True - * @min 0.1 - * @max 3.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_YSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO0_PRIO, -1); /** - * Magnetometer 2 Y-axis scaling factor + * Gyroscope 1 priority * * * * @group Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True - * @min 0.1 - * @max 3.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_YSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO1_PRIO, -1); /** - * Magnetometer 3 Y-axis scaling factor + * Gyroscope 2 priority * * * * @group Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True - * @min 0.1 - * @max 3.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_YSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO2_PRIO, -1); /** - * Magnetometer 0 Z-axis scaling factor + * Gyroscope 3 priority * * * * @group Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True - * @min 0.1 - * @max 3.0 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO3_PRIO, -1); /** - * Magnetometer 1 Z-axis scaling factor + * Gyroscope 0 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 - * @decimal 3 + * @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 - * @volatile True - * @min 0.1 - * @max 3.0 + * @min -1 + * @max 40 */ -PARAM_DEFINE_FLOAT(CAL_MAG1_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO0_ROT, -1); /** - * Magnetometer 2 Z-axis scaling factor + * Gyroscope 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 Sensor Calibration - * @decimal 3 + * @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 - * @volatile True - * @min 0.1 - * @max 3.0 + * @min -1 + * @max 40 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO1_ROT, -1); /** - * Magnetometer 3 Z-axis scaling factor + * Gyroscope 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 - * @decimal 3 + * @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 - * @volatile True - * @min 0.1 - * @max 3.0 + * @min -1 + * @max 40 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_ZSCALE, 1.0); +PARAM_DEFINE_INT32(CAL_GYRO2_ROT, -1); /** - * Magnetometer 0 X-axis off diagonal scale factor + * Gyroscope 3 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 - * @decimal 3 + * @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 - * @volatile True + * @min -1 + * @max 40 */ -PARAM_DEFINE_FLOAT(CAL_MAG0_XODIAG, 0.0); +PARAM_DEFINE_INT32(CAL_GYRO3_ROT, -1); /** - * Magnetometer 1 X-axis off diagonal scale factor + * Gyroscope 0 X-axis offset * * * @@ -2439,11 +2938,12 @@ PARAM_DEFINE_FLOAT(CAL_MAG0_XODIAG, 0.0); * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG1_XODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO0_XOFF, 0.0); /** - * Magnetometer 2 X-axis off diagonal scale factor + * Gyroscope 1 X-axis offset * * * @@ -2451,11 +2951,12 @@ PARAM_DEFINE_FLOAT(CAL_MAG1_XODIAG, 0.0); * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG2_XODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO1_XOFF, 0.0); /** - * Magnetometer 3 X-axis off diagonal scale factor + * Gyroscope 2 X-axis offset * * * @@ -2463,11 +2964,12 @@ PARAM_DEFINE_FLOAT(CAL_MAG2_XODIAG, 0.0); * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG3_XODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO2_XOFF, 0.0); /** - * Magnetometer 0 Y-axis off diagonal scale factor + * Gyroscope 3 X-axis offset * * * @@ -2475,11 +2977,12 @@ PARAM_DEFINE_FLOAT(CAL_MAG3_XODIAG, 0.0); * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG0_YODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO3_XOFF, 0.0); /** - * Magnetometer 1 Y-axis off diagonal scale factor + * Gyroscope 0 Y-axis offset * * * @@ -2487,11 +2990,12 @@ PARAM_DEFINE_FLOAT(CAL_MAG0_YODIAG, 0.0); * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG1_YODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0); /** - * Magnetometer 2 Y-axis off diagonal scale factor + * Gyroscope 1 Y-axis offset * * * @@ -2499,11 +3003,12 @@ PARAM_DEFINE_FLOAT(CAL_MAG1_YODIAG, 0.0); * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG2_YODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0); /** - * Magnetometer 3 Y-axis off diagonal scale factor + * Gyroscope 2 Y-axis offset * * * @@ -2511,7630 +3016,7304 @@ PARAM_DEFINE_FLOAT(CAL_MAG2_YODIAG, 0.0); * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG3_YODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0); /** - * Magnetometer 0 Z-axis off diagonal scale factor + * Gyroscope 3 Y-axis offset * * * * @group Sensor Calibration + * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG0_ZODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO3_YOFF, 0.0); /** - * Magnetometer 1 Z-axis off diagonal scale factor + * Gyroscope 0 Z-axis offset * * * * @group Sensor Calibration + * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG1_ZODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0); /** - * Magnetometer 2 Z-axis off diagonal scale factor + * Gyroscope 1 Z-axis offset * * * * @group Sensor Calibration + * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG2_ZODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0); /** - * Magnetometer 3 Z-axis off diagonal scale factor + * Gyroscope 2 Z-axis offset * * * * @group Sensor Calibration + * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG3_ZODIAG, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0); /** - * Magnetometer 0 X Axis throttle compensation + * Gyroscope 3 Z-axis offset * - * 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 Sensor Calibration * @decimal 3 * @category System * @volatile True + * @unit rad/s */ -PARAM_DEFINE_FLOAT(CAL_MAG0_XCOMP, 0.0); +PARAM_DEFINE_FLOAT(CAL_GYRO3_ZOFF, 0.0); /** - * Magnetometer 1 X Axis throttle compensation + * Magnetometer 0 calibration device ID * - * 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] - * + * Device ID of the magnetometer this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True */ -PARAM_DEFINE_FLOAT(CAL_MAG1_XCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG0_ID, 0); /** - * Magnetometer 2 X Axis throttle compensation + * Magnetometer 1 calibration device ID * - * 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] - * + * Device ID of the magnetometer this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True */ -PARAM_DEFINE_FLOAT(CAL_MAG2_XCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG1_ID, 0); /** - * Magnetometer 3 X Axis throttle compensation + * Magnetometer 2 calibration device ID * - * 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] - * + * Device ID of the magnetometer this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True */ -PARAM_DEFINE_FLOAT(CAL_MAG3_XCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG2_ID, 0); /** - * Magnetometer 0 Y Axis throttle compensation + * Magnetometer 3 calibration device ID * - * 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] - * + * Device ID of the magnetometer this calibration applies to. * * @group Sensor Calibration - * @decimal 3 * @category System - * @volatile True */ -PARAM_DEFINE_FLOAT(CAL_MAG0_YCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG3_ID, 0); /** - * Magnetometer 1 Y Axis throttle compensation + * Magnetometer 0 priority * - * 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 Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True */ -PARAM_DEFINE_FLOAT(CAL_MAG1_YCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG0_PRIO, -1); /** - * Magnetometer 2 Y Axis throttle compensation + * Magnetometer 1 priority * - * 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 Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True */ -PARAM_DEFINE_FLOAT(CAL_MAG2_YCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG1_PRIO, -1); /** - * Magnetometer 3 Y Axis throttle compensation + * Magnetometer 2 priority * - * 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 Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True */ -PARAM_DEFINE_FLOAT(CAL_MAG3_YCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG2_PRIO, -1); /** - * Magnetometer 0 Z Axis throttle compensation + * Magnetometer 3 priority * - * 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 Sensor Calibration - * @decimal 3 + * @value -1 Uninitialized + * @value 0 Disabled + * @value 1 Min + * @value 25 Low + * @value 50 Medium (Default) + * @value 75 High + * @value 100 Max * @category System - * @volatile True */ -PARAM_DEFINE_FLOAT(CAL_MAG0_ZCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG3_PRIO, -1); /** - * Magnetometer 1 Z Axis throttle compensation + * Magnetometer 0 rotation relative to airframe * - * 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] + * 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 - * @decimal 3 - * @category System - * @volatile True - */ -PARAM_DEFINE_FLOAT(CAL_MAG1_ZCOMP, 0.0); - -/** - * Magnetometer 2 Z Axis throttle compensation + * @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 * - * 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] + * 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 - * @decimal 3 + * @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 - * @volatile True + * @min -1 + * @max 40 */ -PARAM_DEFINE_FLOAT(CAL_MAG2_ZCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG1_ROT, -1); /** - * Magnetometer 3 Z Axis throttle compensation + * Magnetometer 2 rotation relative to airframe * - * 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] + * 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 - * @decimal 3 + * @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 - * @volatile True + * @min -1 + * @max 40 */ -PARAM_DEFINE_FLOAT(CAL_MAG3_ZCOMP, 0.0); +PARAM_DEFINE_INT32(CAL_MAG2_ROT, -1); /** - * Empty cell voltage (5C load) + * Magnetometer 3 rotation relative to airframe * - * 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. + * 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 Battery Calibration - * @decimal 2 - * @increment 0.01 - * @unit V - * @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_FLOAT(BAT1_V_EMPTY, 3.6); +PARAM_DEFINE_INT32(CAL_MAG3_ROT, -1); /** - * Empty cell voltage (5C load) + * Magnetometer 0 X-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 gauss */ -PARAM_DEFINE_FLOAT(BAT2_V_EMPTY, 3.6); +PARAM_DEFINE_FLOAT(CAL_MAG0_XOFF, 0.0); /** - * Full cell voltage (5C load) + * Magnetometer 1 X-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 gauss */ -PARAM_DEFINE_FLOAT(BAT1_V_CHARGED, 4.05); +PARAM_DEFINE_FLOAT(CAL_MAG1_XOFF, 0.0); /** - * Full cell voltage (5C load) + * Magnetometer 2 X-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 gauss */ -PARAM_DEFINE_FLOAT(BAT2_V_CHARGED, 4.05); +PARAM_DEFINE_FLOAT(CAL_MAG2_XOFF, 0.0); /** - * Voltage drop per cell on full throttle + * Magnetometer 3 X-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 gauss */ -PARAM_DEFINE_FLOAT(BAT1_V_LOAD_DROP, 0.1); +PARAM_DEFINE_FLOAT(CAL_MAG3_XOFF, 0.0); /** - * Voltage drop per cell on full throttle + * Magnetometer 0 Y-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 gauss */ -PARAM_DEFINE_FLOAT(BAT2_V_LOAD_DROP, 0.1); +PARAM_DEFINE_FLOAT(CAL_MAG0_YOFF, 0.0); /** - * Explicitly defines the per cell internal resistance for battery 1 + * Magnetometer 1 Y-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 gauss */ -PARAM_DEFINE_FLOAT(BAT1_R_INTERNAL, 0.005); +PARAM_DEFINE_FLOAT(CAL_MAG1_YOFF, 0.0); /** - * Explicitly defines the per cell internal resistance for battery 2 + * Magnetometer 2 Y-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 gauss */ -PARAM_DEFINE_FLOAT(BAT2_R_INTERNAL, 0.005); +PARAM_DEFINE_FLOAT(CAL_MAG2_YOFF, 0.0); /** - * Number of cells for battery 1. + * Magnetometer 3 Y-axis offset * - * 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 + * @unit gauss */ -PARAM_DEFINE_INT32(BAT1_N_CELLS, 0); +PARAM_DEFINE_FLOAT(CAL_MAG3_YOFF, 0.0); /** - * Number of cells for battery 2. + * Magnetometer 0 Z-axis offset * - * 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 + * @unit gauss */ -PARAM_DEFINE_INT32(BAT2_N_CELLS, 0); +PARAM_DEFINE_FLOAT(CAL_MAG0_ZOFF, 0.0); /** - * Battery 1 capacity. + * Magnetometer 1 Z-axis offset * - * 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 + * @unit gauss */ -PARAM_DEFINE_FLOAT(BAT1_CAPACITY, -1.0); +PARAM_DEFINE_FLOAT(CAL_MAG1_ZOFF, 0.0); /** - * Battery 2 capacity. + * Magnetometer 2 Z-axis offset * - * 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 + * @unit gauss */ -PARAM_DEFINE_FLOAT(BAT2_CAPACITY, -1.0); +PARAM_DEFINE_FLOAT(CAL_MAG2_ZOFF, 0.0); /** - * Battery 1 monitoring source. + * Magnetometer 3 Z-axis offset * - * 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 + * @unit gauss */ -PARAM_DEFINE_INT32(BAT1_SOURCE, 0); +PARAM_DEFINE_FLOAT(CAL_MAG3_ZOFF, 0.0); /** - * Battery 2 monitoring source. + * Magnetometer 0 X-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_MAG0_XSCALE, 1.0); /** - * RC input protocol + * Magnetometer 1 X-axis scaling factor * - * Select your RC input protocol or auto to scan. * * - * @group RC Input - * @value -1 Auto - * @value 0 None - * @value 1 PPM - * @value 2 SBUS - * @value 3 DSM - * @value 4 ST24 - * @value 5 SUMD - * @value 6 CRSF - * @value 7 GHST + * @group Sensor Calibration + * @decimal 3 * @category System - * @min -1 - * @max 7 + * @volatile True + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(RC_INPUT_PROTO, -1); +PARAM_DEFINE_FLOAT(CAL_MAG1_XSCALE, 1.0); /** - * SIM_GZ ESC 1 Output Function + * Magnetometer 2 X-axis scaling factor * - * 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 * * - * @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 + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC1, 0); +PARAM_DEFINE_FLOAT(CAL_MAG2_XSCALE, 1.0); /** - * SIM_GZ ESC 2 Output Function + * Magnetometer 3 X-axis scaling factor * - * 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 * * - * @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 + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC2, 0); +PARAM_DEFINE_FLOAT(CAL_MAG3_XSCALE, 1.0); /** - * SIM_GZ ESC 3 Output Function + * Magnetometer 0 Y-axis scaling factor * - * 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 - * @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 + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC3, 0); +PARAM_DEFINE_FLOAT(CAL_MAG0_YSCALE, 1.0); /** - * SIM_GZ ESC 4 Output Function + * Magnetometer 1 Y-axis scaling factor * - * 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 - * @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 + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC4, 0); +PARAM_DEFINE_FLOAT(CAL_MAG1_YSCALE, 1.0); /** - * SIM_GZ ESC 5 Output Function + * Magnetometer 2 Y-axis scaling factor * - * 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 Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 + */ +PARAM_DEFINE_FLOAT(CAL_MAG2_YSCALE, 1.0); + +/** + * Magnetometer 3 Y-axis scaling factor + * * * - * @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 + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC5, 0); +PARAM_DEFINE_FLOAT(CAL_MAG3_YSCALE, 1.0); /** - * SIM_GZ ESC 6 Output Function + * Magnetometer 0 Z-axis scaling factor * - * 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 Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 + */ +PARAM_DEFINE_FLOAT(CAL_MAG0_ZSCALE, 1.0); + +/** + * Magnetometer 1 Z-axis scaling factor + * * * - * @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 + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC6, 0); +PARAM_DEFINE_FLOAT(CAL_MAG1_ZSCALE, 1.0); /** - * SIM_GZ ESC 7 Output Function + * Magnetometer 2 Z-axis scaling factor * - * 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 Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + * @min 0.1 + * @max 3.0 + */ +PARAM_DEFINE_FLOAT(CAL_MAG2_ZSCALE, 1.0); + +/** + * Magnetometer 3 Z-axis scaling factor + * * * - * @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 + * @min 0.1 + * @max 3.0 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC7, 0); +PARAM_DEFINE_FLOAT(CAL_MAG3_ZSCALE, 1.0); /** - * SIM_GZ ESC 8 Output Function + * Magnetometer 0 X-axis off diagonal scale factor * - * 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 Sensor Calibration + * @decimal 3 + * @category System + * @volatile True + */ +PARAM_DEFINE_FLOAT(CAL_MAG0_XODIAG, 0.0); + +/** + * Magnetometer 1 X-axis off diagonal scale factor + * * * - * @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_MAG1_XODIAG, 0.0); /** - * SIM_GZ ESC 1 Disarmed Value + * Magnetometer 2 X-axis off diagonal scale factor * - * 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_MAG2_XODIAG, 0.0); /** - * SIM_GZ ESC 2 Disarmed Value + * Magnetometer 3 X-axis off diagonal scale factor * - * 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_MAG3_XODIAG, 0.0); /** - * SIM_GZ ESC 3 Disarmed Value + * Magnetometer 0 Y-axis off diagonal scale factor * - * 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_DIS3, 0); +PARAM_DEFINE_FLOAT(CAL_MAG0_YODIAG, 0.0); /** - * SIM_GZ ESC 4 Disarmed Value + * Magnetometer 1 Y-axis off diagonal scale factor * - * 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_DIS4, 0); +PARAM_DEFINE_FLOAT(CAL_MAG1_YODIAG, 0.0); /** - * SIM_GZ ESC 5 Disarmed Value + * Magnetometer 2 Y-axis off diagonal scale factor * - * 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_DIS5, 0); +PARAM_DEFINE_FLOAT(CAL_MAG2_YODIAG, 0.0); /** - * SIM_GZ ESC 6 Disarmed Value + * Magnetometer 3 Y-axis off diagonal scale factor * - * 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_DIS6, 0); +PARAM_DEFINE_FLOAT(CAL_MAG3_YODIAG, 0.0); /** - * SIM_GZ ESC 7 Disarmed Value + * Magnetometer 0 Z-axis off diagonal scale factor * - * 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 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS7, 0); +PARAM_DEFINE_FLOAT(CAL_MAG0_ZODIAG, 0.0); /** - * SIM_GZ ESC 8 Disarmed Value + * Magnetometer 1 Z-axis off diagonal scale factor * - * 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 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_DIS8, 0); +PARAM_DEFINE_FLOAT(CAL_MAG1_ZODIAG, 0.0); /** - * SIM_GZ ESC 1 Minimum Value + * Magnetometer 2 Z-axis off diagonal scale factor * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN1, 0); +PARAM_DEFINE_FLOAT(CAL_MAG2_ZODIAG, 0.0); /** - * SIM_GZ ESC 2 Minimum Value + * Magnetometer 3 Z-axis off diagonal scale factor * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN2, 0); +PARAM_DEFINE_FLOAT(CAL_MAG3_ZODIAG, 0.0); /** - * SIM_GZ ESC 3 Minimum Value + * Magnetometer 0 X Axis throttle compensation * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN3, 0); +PARAM_DEFINE_FLOAT(CAL_MAG0_XCOMP, 0.0); /** - * SIM_GZ ESC 4 Minimum Value + * Magnetometer 1 X Axis throttle compensation * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN4, 0); +PARAM_DEFINE_FLOAT(CAL_MAG1_XCOMP, 0.0); /** - * SIM_GZ ESC 5 Minimum Value + * Magnetometer 2 X Axis throttle compensation * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN5, 0); +PARAM_DEFINE_FLOAT(CAL_MAG2_XCOMP, 0.0); /** - * SIM_GZ ESC 6 Minimum Value + * Magnetometer 3 X Axis throttle compensation * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN6, 0); +PARAM_DEFINE_FLOAT(CAL_MAG3_XCOMP, 0.0); /** - * SIM_GZ ESC 7 Minimum Value - * - * Minimum output value (when not disarmed). - * + * Magnetometer 0 Y Axis throttle compensation * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * 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 Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN7, 0); +PARAM_DEFINE_FLOAT(CAL_MAG0_YCOMP, 0.0); /** - * SIM_GZ ESC 8 Minimum Value + * Magnetometer 1 Y Axis throttle compensation * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MIN8, 0); +PARAM_DEFINE_FLOAT(CAL_MAG1_YCOMP, 0.0); /** - * SIM_GZ ESC 1 Maximum Value + * Magnetometer 2 Y Axis throttle compensation * - * Maxmimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX1, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG2_YCOMP, 0.0); /** - * SIM_GZ ESC 2 Maximum Value + * Magnetometer 3 Y Axis throttle compensation * - * Maxmimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX2, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG3_YCOMP, 0.0); /** - * SIM_GZ ESC 3 Maximum Value + * Magnetometer 0 Z Axis throttle compensation * - * Maxmimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX3, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG0_ZCOMP, 0.0); /** - * SIM_GZ ESC 4 Maximum Value + * Magnetometer 1 Z Axis throttle compensation * - * Maxmimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX4, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG1_ZCOMP, 0.0); /** - * SIM_GZ ESC 5 Maximum Value + * Magnetometer 2 Z Axis throttle compensation * - * Maxmimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX5, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG2_ZCOMP, 0.0); /** - * SIM_GZ ESC 6 Maximum Value + * Magnetometer 3 Z Axis throttle compensation * - * Maxmimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Sensor Calibration + * @decimal 3 + * @category System + * @volatile True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX6, 1000); +PARAM_DEFINE_FLOAT(CAL_MAG3_ZCOMP, 0.0); /** - * SIM_GZ ESC 7 Maximum Value + * Battery 1 voltage divider (V divider) * - * Maxmimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Battery Calibration + * @decimal 8 + * @reboot_required True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX7, 1000); +PARAM_DEFINE_FLOAT(BAT1_V_DIV, -1.0); /** - * SIM_GZ ESC 8 Maximum Value + * Battery 2 voltage divider (V divider) * - * Maxmimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Battery Calibration + * @decimal 8 + * @reboot_required True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_MAX8, 1000); +PARAM_DEFINE_FLOAT(BAT2_V_DIV, -1.0); /** - * SIM_GZ ESC 1 Failsafe Value + * Battery 1 current per volt (A/V) * - * 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). + * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @group Battery Calibration + * @decimal 8 + * @reboot_required True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL1, -1); +PARAM_DEFINE_FLOAT(BAT1_A_PER_V, -1.0); /** - * SIM_GZ ESC 2 Failsafe Value + * Battery 2 current per volt (A/V) * - * 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). + * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @group Battery Calibration + * @decimal 8 + * @reboot_required True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL2, -1); +PARAM_DEFINE_FLOAT(BAT2_A_PER_V, -1.0); /** - * SIM_GZ ESC 3 Failsafe Value + * Battery 1 Voltage ADC Channel * - * 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). + * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @group Battery Calibration + * @reboot_required True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL3, -1); +PARAM_DEFINE_INT32(BAT1_V_CHANNEL, -1); /** - * SIM_GZ ESC 4 Failsafe Value + * Battery 2 Voltage ADC Channel * - * 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). + * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @group Battery Calibration + * @reboot_required True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL4, -1); +PARAM_DEFINE_INT32(BAT2_V_CHANNEL, -1); /** - * SIM_GZ ESC 5 Failsafe Value + * Battery 1 Current ADC Channel * - * 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). + * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @group Battery Calibration + * @reboot_required True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL5, -1); +PARAM_DEFINE_INT32(BAT1_I_CHANNEL, -1); /** - * SIM_GZ ESC 6 Failsafe Value + * Battery 2 Current ADC Channel * - * 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). + * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @group Battery Calibration + * @reboot_required True */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL6, -1); +PARAM_DEFINE_INT32(BAT2_I_CHANNEL, -1); /** - * SIM_GZ ESC 7 Failsafe Value + * Airframe selection * - * This is the output value that is set when in failsafe mode. + * Defines which mixer implementation to use. + * Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. * - * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC7). + * 'Custom' should only be used if noting else can be used. * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @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 */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL7, -1); +PARAM_DEFINE_INT32(CA_AIRFRAME, 0); /** - * SIM_GZ ESC 8 Failsafe Value + * Control allocation method * - * 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). + * Selects the algorithm and desaturation method. + * If set to Automtic, the selection is based on the airframe (CA_AIRFRAME). * * - * @group Actuator Outputs - * @min -1 - * @max 1000 + * @group Geometry + * @value 0 Pseudo-inverse with output clipping + * @value 1 Pseudo-inverse with sequential desaturation technique + * @value 2 Automatic */ -PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL8, -1); +PARAM_DEFINE_INT32(CA_METHOD, 2); /** - * SIM_GZ Servo 1 Output Function + * Bidirectional/Reversible motors * - * 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 + * Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well. * * - * @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 + * @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_INT32(SIM_GZ_SV_FUNC1, 0); +PARAM_DEFINE_INT32(CA_R_REV, 0); /** - * SIM_GZ Servo 2 Output Function + * Motor 0 slew rate limit * - * Select what should be output on SIM_GZ Servo 2. + * 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). * - * 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 + * Zero means that slew rate limiting is disabled. * * - * @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 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC2, 0); +PARAM_DEFINE_FLOAT(CA_R0_SLEW, 0.0); /** - * SIM_GZ Servo 3 Output Function + * Motor 1 slew rate limit * - * Select what should be output on SIM_GZ Servo 3. + * 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). * - * 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 + * Zero means that slew rate limiting is disabled. * * - * @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 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC3, 0); +PARAM_DEFINE_FLOAT(CA_R1_SLEW, 0.0); /** - * SIM_GZ Servo 4 Output Function + * Motor 2 slew rate limit * - * Select what should be output on SIM_GZ Servo 4. + * 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). * - * 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 + * Zero means that slew rate limiting is disabled. * * - * @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 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC4, 0); +PARAM_DEFINE_FLOAT(CA_R2_SLEW, 0.0); /** - * SIM_GZ Servo 5 Output Function + * Motor 3 slew rate limit * - * Select what should be output on SIM_GZ Servo 5. + * 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). * - * 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 + * Zero means that slew rate limiting is disabled. * * - * @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 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC5, 0); +PARAM_DEFINE_FLOAT(CA_R3_SLEW, 0.0); /** - * SIM_GZ Servo 6 Output Function + * Motor 4 slew rate limit * - * Select what should be output on SIM_GZ Servo 6. + * 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). * - * 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 + * Zero means that slew rate limiting is disabled. * * - * @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 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC6, 0); +PARAM_DEFINE_FLOAT(CA_R4_SLEW, 0.0); /** - * SIM_GZ Servo 7 Output Function + * Motor 5 slew rate limit * - * Select what should be output on SIM_GZ Servo 7. + * 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). * - * 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 + * Zero means that slew rate limiting is disabled. * * - * @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 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC7, 0); +PARAM_DEFINE_FLOAT(CA_R5_SLEW, 0.0); /** - * SIM_GZ Servo 8 Output Function + * Motor 6 slew rate limit * - * Select what should be output on SIM_GZ Servo 8. + * 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). * - * 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 + * Zero means that slew rate limiting is disabled. * * - * @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 2 + * @increment 0.01 + * @min 0 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC8, 0); +PARAM_DEFINE_FLOAT(CA_R6_SLEW, 0.0); /** - * SIM_GZ Servo 1 Disarmed Value + * Motor 7 slew rate limit * - * This is the output value that is set when not armed. + * 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). * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Zero means that slew rate limiting is disabled. * * - * @group Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.01 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS1, 500); +PARAM_DEFINE_FLOAT(CA_R7_SLEW, 0.0); /** - * SIM_GZ Servo 2 Disarmed Value + * Motor 8 slew rate limit * - * This is the output value that is set when not armed. + * 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). * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Zero means that slew rate limiting is disabled. * * - * @group Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.01 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS2, 500); +PARAM_DEFINE_FLOAT(CA_R8_SLEW, 0.0); /** - * SIM_GZ Servo 3 Disarmed Value + * Motor 9 slew rate limit * - * This is the output value that is set when not armed. + * 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). * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Zero means that slew rate limiting is disabled. * * - * @group Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.01 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS3, 500); +PARAM_DEFINE_FLOAT(CA_R9_SLEW, 0.0); /** - * SIM_GZ Servo 4 Disarmed Value + * Motor 10 slew rate limit * - * This is the output value that is set when not armed. + * 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). * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Zero means that slew rate limiting is disabled. * * - * @group Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.01 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS4, 500); +PARAM_DEFINE_FLOAT(CA_R10_SLEW, 0.0); /** - * SIM_GZ Servo 5 Disarmed Value + * Motor 11 slew rate limit * - * This is the output value that is set when not armed. + * 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). * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Zero means that slew rate limiting is disabled. * * - * @group Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.01 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS5, 500); +PARAM_DEFINE_FLOAT(CA_R11_SLEW, 0.0); /** - * SIM_GZ Servo 6 Disarmed Value + * Servo 0 slew rate limit * - * This is the output value that is set when not armed. + * 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. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Zero means that slew rate limiting is disabled. * * - * @group Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.05 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS6, 500); +PARAM_DEFINE_FLOAT(CA_SV0_SLEW, 0.0); /** - * SIM_GZ Servo 7 Disarmed Value + * Servo 1 slew rate limit * - * This is the output value that is set when not armed. + * 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. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Zero means that slew rate limiting is disabled. * * - * @group Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.05 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS7, 500); +PARAM_DEFINE_FLOAT(CA_SV1_SLEW, 0.0); /** - * SIM_GZ Servo 8 Disarmed Value + * Servo 2 slew rate limit * - * This is the output value that is set when not armed. + * 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. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Zero means that slew rate limiting is disabled. * * - * @group Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.05 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_DIS8, 500); +PARAM_DEFINE_FLOAT(CA_SV2_SLEW, 0.0); /** - * SIM_GZ Servo 1 Minimum Value + * Servo 3 slew rate limit * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.05 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN1, 0); +PARAM_DEFINE_FLOAT(CA_SV3_SLEW, 0.0); /** - * SIM_GZ Servo 2 Minimum Value + * Servo 4 slew rate limit * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.05 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN2, 0); +PARAM_DEFINE_FLOAT(CA_SV4_SLEW, 0.0); /** - * SIM_GZ Servo 3 Minimum Value + * Servo 5 slew rate limit * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.05 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN3, 0); +PARAM_DEFINE_FLOAT(CA_SV5_SLEW, 0.0); /** - * SIM_GZ Servo 4 Minimum Value + * Servo 6 slew rate limit * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.05 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN4, 0); +PARAM_DEFINE_FLOAT(CA_SV6_SLEW, 0.0); /** - * SIM_GZ Servo 5 Minimum Value + * Servo 7 slew rate limit * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs + * @group Geometry + * @decimal 2 + * @increment 0.05 * @min 0 - * @max 1000 + * @max 10 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN5, 0); +PARAM_DEFINE_FLOAT(CA_SV7_SLEW, 0.0); /** - * SIM_GZ Servo 6 Minimum Value + * Total number of rotors * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @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 */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN6, 0); +PARAM_DEFINE_INT32(CA_ROTOR_COUNT, 0); /** - * SIM_GZ Servo 7 Minimum Value + * Position of rotor 0 along X body axis * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN7, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR0_PX, 0.0); /** - * SIM_GZ Servo 8 Minimum Value + * Position of rotor 1 along X body axis * - * Minimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MIN8, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR1_PX, 0.0); /** - * SIM_GZ Servo 1 Maximum Value + * Position of rotor 2 along X body axis * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX1, 1000); +PARAM_DEFINE_FLOAT(CA_ROTOR2_PX, 0.0); /** - * SIM_GZ Servo 2 Maximum Value + * Position of rotor 3 along X body axis * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX2, 1000); +PARAM_DEFINE_FLOAT(CA_ROTOR3_PX, 0.0); /** - * SIM_GZ Servo 3 Maximum Value + * Position of rotor 4 along X body axis * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX3, 1000); +PARAM_DEFINE_FLOAT(CA_ROTOR4_PX, 0.0); /** - * SIM_GZ Servo 4 Maximum Value + * Position of rotor 5 along X body axis * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX4, 1000); +PARAM_DEFINE_FLOAT(CA_ROTOR5_PX, 0.0); /** - * SIM_GZ Servo 5 Maximum Value + * Position of rotor 6 along X body axis * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX5, 1000); +PARAM_DEFINE_FLOAT(CA_ROTOR6_PX, 0.0); /** - * SIM_GZ Servo 6 Maximum Value + * Position of rotor 7 along X body axis * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX6, 1000); +PARAM_DEFINE_FLOAT(CA_ROTOR7_PX, 0.0); /** - * SIM_GZ Servo 7 Maximum Value + * Position of rotor 8 along X body axis * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX7, 1000); +PARAM_DEFINE_FLOAT(CA_ROTOR8_PX, 0.0); /** - * SIM_GZ Servo 8 Maximum Value + * Position of rotor 9 along X body axis * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_MAX8, 1000); +PARAM_DEFINE_FLOAT(CA_ROTOR9_PX, 0.0); /** - * SIM_GZ Servo 1 Failsafe Value + * Position of rotor 10 along X body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL1, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR10_PX, 0.0); /** - * SIM_GZ Servo 2 Failsafe Value + * Position of rotor 11 along X body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL2, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR11_PX, 0.0); /** - * SIM_GZ Servo 3 Failsafe Value + * Position of rotor 0 along Y body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL3, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR0_PY, 0.0); /** - * SIM_GZ Servo 4 Failsafe Value + * Position of rotor 1 along Y body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL4, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR1_PY, 0.0); /** - * SIM_GZ Servo 5 Failsafe Value + * Position of rotor 2 along Y body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL5, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR2_PY, 0.0); /** - * SIM_GZ Servo 6 Failsafe Value + * Position of rotor 3 along Y body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL6, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR3_PY, 0.0); /** - * SIM_GZ Servo 7 Failsafe Value + * Position of rotor 4 along Y body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL7, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR4_PY, 0.0); /** - * SIM_GZ Servo 8 Failsafe Value + * Position of rotor 5 along Y body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL8, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR5_PY, 0.0); /** - * Reverse Output Range for SIM_GZ + * Position of rotor 6 along Y body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_EC_REV, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR6_PY, 0.0); /** - * Reverse Output Range for SIM_GZ + * Position of rotor 7 along Y body axis * - * 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 Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(SIM_GZ_SV_REV, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR7_PY, 0.0); /** - * UAVCAN ESC 1 Output Function + * Position of rotor 8 along Y body axis * - * 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 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 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC1, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR8_PY, 0.0); /** - * UAVCAN ESC 2 Output Function + * Position of rotor 9 along Y body axis * - * 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 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 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC2, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR9_PY, 0.0); /** - * UAVCAN ESC 3 Output Function + * Position of rotor 10 along Y body axis * - * 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 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR10_PY, 0.0); + +/** + * Position of rotor 11 along Y body axis + * * * - * @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 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC3, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_PY, 0.0); /** - * UAVCAN ESC 4 Output Function + * Position of rotor 0 along Z body axis * - * 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 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR0_PZ, 0.0); + +/** + * Position of rotor 1 along Z body axis + * * * - * @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 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC4, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR1_PZ, 0.0); /** - * UAVCAN ESC 5 Output Function + * Position of rotor 2 along Z body axis * - * 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 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR2_PZ, 0.0); + +/** + * Position of rotor 3 along Z body axis + * * * - * @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 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC5, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR3_PZ, 0.0); /** - * UAVCAN ESC 6 Output Function + * Position of rotor 4 along Z body axis * - * 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 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR4_PZ, 0.0); + +/** + * Position of rotor 5 along Z body axis + * * * - * @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 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC6, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR5_PZ, 0.0); /** - * UAVCAN ESC 7 Output Function + * Position of rotor 6 along Z body axis * - * 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 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR6_PZ, 0.0); + +/** + * Position of rotor 7 along Z body axis + * * * - * @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 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR7_PZ, 0.0); + +/** + * Position of rotor 8 along Z body axis + * + * + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR8_PZ, 0.0); + +/** + * Position of rotor 9 along Z body axis + * + * + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR9_PZ, 0.0); + +/** + * Position of rotor 10 along Z body axis + * + * + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR10_PZ, 0.0); + +/** + * Position of rotor 11 along Z body axis + * + * + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + * @unit m + */ +PARAM_DEFINE_FLOAT(CA_ROTOR11_PZ, 0.0); + +/** + * Axis of rotor 0 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR0_AX, 0.0); + +/** + * Axis of rotor 1 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR1_AX, 0.0); + +/** + * Axis of rotor 2 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR2_AX, 0.0); + +/** + * Axis of rotor 3 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR3_AX, 0.0); + +/** + * Axis of rotor 4 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR4_AX, 0.0); + +/** + * Axis of rotor 5 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR5_AX, 0.0); + +/** + * Axis of rotor 6 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR6_AX, 0.0); + +/** + * Axis of rotor 7 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR7_AX, 0.0); + +/** + * Axis of rotor 8 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR8_AX, 0.0); + +/** + * Axis of rotor 9 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR9_AX, 0.0); + +/** + * Axis of rotor 10 thrust vector, X body axis component + * + * Only the direction is considered (the vector is normalized). + * + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC7, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR10_AX, 0.0); /** - * UAVCAN ESC 8 Output Function + * Axis of rotor 11 thrust vector, X body axis component * - * 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 - * + * Only the direction is considered (the vector is normalized). * - * @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 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FUNC8, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_AX, 0.0); /** - * UAVCAN ESC 1 Minimum Value + * Axis of rotor 0 thrust vector, Y body axis component * - * Minimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN1, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR0_AY, 0.0); /** - * UAVCAN ESC 2 Minimum Value + * Axis of rotor 1 thrust vector, Y body axis component * - * Minimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN2, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR1_AY, 0.0); /** - * UAVCAN ESC 3 Minimum Value + * Axis of rotor 2 thrust vector, Y body axis component * - * Minimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN3, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR2_AY, 0.0); /** - * UAVCAN ESC 4 Minimum Value + * Axis of rotor 3 thrust vector, Y body axis component * - * Minimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN4, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR3_AY, 0.0); /** - * UAVCAN ESC 5 Minimum Value + * Axis of rotor 4 thrust vector, Y body axis component * - * Minimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN5, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR4_AY, 0.0); /** - * UAVCAN ESC 6 Minimum Value + * Axis of rotor 5 thrust vector, Y body axis component * - * Minimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN6, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR5_AY, 0.0); /** - * UAVCAN ESC 7 Minimum Value + * Axis of rotor 6 thrust vector, Y body axis component * - * Minimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN7, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR6_AY, 0.0); /** - * UAVCAN ESC 8 Minimum Value + * Axis of rotor 7 thrust vector, Y body axis component * - * Minimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MIN8, 1); +PARAM_DEFINE_FLOAT(CA_ROTOR7_AY, 0.0); /** - * UAVCAN ESC 1 Maximum Value + * Axis of rotor 8 thrust vector, Y body axis component * - * Maxmimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX1, 8191); +PARAM_DEFINE_FLOAT(CA_ROTOR8_AY, 0.0); /** - * UAVCAN ESC 2 Maximum Value + * Axis of rotor 9 thrust vector, Y body axis component * - * Maxmimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX2, 8191); +PARAM_DEFINE_FLOAT(CA_ROTOR9_AY, 0.0); /** - * UAVCAN ESC 3 Maximum Value + * Axis of rotor 10 thrust vector, Y body axis component * - * Maxmimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX3, 8191); +PARAM_DEFINE_FLOAT(CA_ROTOR10_AY, 0.0); /** - * UAVCAN ESC 4 Maximum Value + * Axis of rotor 11 thrust vector, Y body axis component * - * Maxmimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX4, 8191); +PARAM_DEFINE_FLOAT(CA_ROTOR11_AY, 0.0); /** - * UAVCAN ESC 5 Maximum Value + * Axis of rotor 0 thrust vector, Z body axis component * - * Maxmimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX5, 8191); +PARAM_DEFINE_FLOAT(CA_ROTOR0_AZ, -1.0); /** - * UAVCAN ESC 6 Maximum Value + * Axis of rotor 1 thrust vector, Z body axis component * - * Maxmimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX6, 8191); +PARAM_DEFINE_FLOAT(CA_ROTOR1_AZ, -1.0); /** - * UAVCAN ESC 7 Maximum Value + * Axis of rotor 2 thrust vector, Z body axis component * - * Maxmimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX7, 8191); +PARAM_DEFINE_FLOAT(CA_ROTOR2_AZ, -1.0); /** - * UAVCAN ESC 8 Maximum Value + * Axis of rotor 3 thrust vector, Z body axis component * - * Maxmimum output value (when not disarmed). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min 0 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_MAX8, 8191); +PARAM_DEFINE_FLOAT(CA_ROTOR3_AZ, -1.0); /** - * UAVCAN ESC 1 Failsafe Value + * Axis of rotor 4 thrust vector, Z body axis component * - * 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). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min -1 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL1, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR4_AZ, -1.0); /** - * UAVCAN ESC 2 Failsafe Value + * Axis of rotor 5 thrust vector, Z body axis component * - * 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). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min -1 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL2, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR5_AZ, -1.0); /** - * UAVCAN ESC 3 Failsafe Value + * Axis of rotor 6 thrust vector, Z body axis component * - * 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). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min -1 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL3, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR6_AZ, -1.0); /** - * UAVCAN ESC 4 Failsafe Value + * Axis of rotor 7 thrust vector, Z body axis component * - * 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). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min -1 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL4, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR7_AZ, -1.0); /** - * UAVCAN ESC 5 Failsafe Value + * Axis of rotor 8 thrust vector, Z body axis component * - * 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). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min -1 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL5, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR8_AZ, -1.0); /** - * UAVCAN ESC 6 Failsafe Value + * Axis of rotor 9 thrust vector, Z body axis component * - * 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). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min -1 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL6, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR9_AZ, -1.0); /** - * UAVCAN ESC 7 Failsafe Value + * Axis of rotor 10 thrust vector, Z body axis component * - * 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). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min -1 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL7, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR10_AZ, -1.0); /** - * UAVCAN ESC 8 Failsafe Value + * Axis of rotor 11 thrust vector, Z body axis component * - * 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). - * + * Only the direction is considered (the vector is normalized). * - * @group Actuator Outputs - * @min -1 - * @max 8191 + * @group Geometry + * @decimal 2 + * @increment 0.1 + * @min -100 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_EC_FAIL8, -1); +PARAM_DEFINE_FLOAT(CA_ROTOR11_AZ, -1.0); /** - * UAVCAN Servo 1 Output Function - * - * 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 - * + * Thrust coefficient of rotor 0 * - * @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 + * 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(UAVCAN_SV_FUNC1, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR0_CT, 6.5); /** - * UAVCAN Servo 2 Output Function + * Thrust coefficient of rotor 1 * - * Select what should be output on UAVCAN Servo 2. + * 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 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR1_CT, 6.5); + +/** + * Thrust coefficient of rotor 2 + * + * 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 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 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC2, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR2_CT, 6.5); /** - * UAVCAN Servo 3 Output Function + * Thrust coefficient of rotor 3 * - * Select what should be output on UAVCAN Servo 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 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR3_CT, 6.5); + +/** + * 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 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 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC3, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR4_CT, 6.5); /** - * UAVCAN Servo 4 Output Function + * Thrust coefficient of rotor 5 * - * Select what should be output on UAVCAN Servo 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. * - * 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 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR5_CT, 6.5); + +/** + * 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 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 1 + * @increment 1 + * @min 0 + * @max 100 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR6_CT, 6.5); + +/** + * 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 Geometry + * @decimal 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC4, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR7_CT, 6.5); /** - * UAVCAN Servo 5 Output Function + * Thrust coefficient of rotor 8 * - * Select what should be output on UAVCAN Servo 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 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR8_CT, 6.5); + +/** + * 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 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 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC5, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR9_CT, 6.5); /** - * UAVCAN Servo 6 Output Function + * Thrust coefficient of rotor 10 * - * Select what should be output on UAVCAN Servo 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. * - * 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 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR10_CT, 6.5); + +/** + * 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 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 1 + * @increment 1 + * @min 0 + * @max 100 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC6, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_CT, 6.5); /** - * UAVCAN Servo 7 Output Function + * Moment coefficient of rotor 0 * - * Select what should be output on UAVCAN Servo 7. + * The moment coefficient if defined as Torque = KM * Thrust. * - * 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 a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @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.01 + * @min -1 + * @max 1 + */ +PARAM_DEFINE_FLOAT(CA_ROTOR0_KM, 0.05); + +/** + * 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 Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC7, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR1_KM, 0.05); /** - * UAVCAN Servo 8 Output Function + * Moment coefficient of rotor 2 * - * Select what should be output on UAVCAN Servo 8. + * The moment coefficient if defined as Torque = KM * Thrust. * - * 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 a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @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.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FUNC8, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR2_KM, 0.05); /** - * UAVCAN Servo 1 Disarmed Value + * Moment coefficient of rotor 3 * - * This is the output value that is set when not armed. + * The moment coefficient if defined as Torque = KM * Thrust. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS1, 500); +PARAM_DEFINE_FLOAT(CA_ROTOR3_KM, 0.05); /** - * UAVCAN Servo 2 Disarmed Value + * Moment coefficient of rotor 4 * - * This is the output value that is set when not armed. + * The moment coefficient if defined as Torque = KM * Thrust. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS2, 500); +PARAM_DEFINE_FLOAT(CA_ROTOR4_KM, 0.05); /** - * UAVCAN Servo 3 Disarmed Value + * Moment coefficient of rotor 5 * - * This is the output value that is set when not armed. + * The moment coefficient if defined as Torque = KM * Thrust. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS3, 500); +PARAM_DEFINE_FLOAT(CA_ROTOR5_KM, 0.05); /** - * UAVCAN Servo 4 Disarmed Value + * Moment coefficient of rotor 6 * - * This is the output value that is set when not armed. + * The moment coefficient if defined as Torque = KM * Thrust. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS4, 500); +PARAM_DEFINE_FLOAT(CA_ROTOR6_KM, 0.05); /** - * UAVCAN Servo 5 Disarmed Value + * Moment coefficient of rotor 7 * - * This is the output value that is set when not armed. + * The moment coefficient if defined as Torque = KM * Thrust. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS5, 500); +PARAM_DEFINE_FLOAT(CA_ROTOR7_KM, 0.05); /** - * UAVCAN Servo 6 Disarmed Value + * Moment coefficient of rotor 8 * - * This is the output value that is set when not armed. + * The moment coefficient if defined as Torque = KM * Thrust. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS6, 500); +PARAM_DEFINE_FLOAT(CA_ROTOR8_KM, 0.05); /** - * UAVCAN Servo 7 Disarmed Value + * Moment coefficient of rotor 9 * - * This is the output value that is set when not armed. + * The moment coefficient if defined as Torque = KM * Thrust. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS7, 500); +PARAM_DEFINE_FLOAT(CA_ROTOR9_KM, 0.05); /** - * UAVCAN Servo 8 Disarmed Value + * Moment coefficient of rotor 10 * - * This is the output value that is set when not armed. + * The moment coefficient if defined as Torque = KM * Thrust. * - * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + * Use a positive value for a rotor with CCW rotation. + * Use a negative value for a rotor with CW rotation. * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_DIS8, 500); +PARAM_DEFINE_FLOAT(CA_ROTOR10_KM, 0.05); /** - * UAVCAN Servo 1 Minimum Value + * Moment coefficient of rotor 11 * - * Minimum output value (when not disarmed). + * 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 Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @decimal 3 + * @increment 0.01 + * @min -1 + * @max 1 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN1, 0); +PARAM_DEFINE_FLOAT(CA_ROTOR11_KM, 0.05); /** - * UAVCAN Servo 2 Minimum Value + * Rotor 0 tilt assignment * - * Minimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN2, 0); +PARAM_DEFINE_INT32(CA_ROTOR0_TILT, 0); /** - * UAVCAN Servo 3 Minimum Value + * Rotor 1 tilt assignment * - * Minimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN3, 0); +PARAM_DEFINE_INT32(CA_ROTOR1_TILT, 0); /** - * UAVCAN Servo 4 Minimum Value + * Rotor 2 tilt assignment * - * Minimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN4, 0); +PARAM_DEFINE_INT32(CA_ROTOR2_TILT, 0); /** - * UAVCAN Servo 5 Minimum Value + * Rotor 3 tilt assignment * - * Minimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN5, 0); +PARAM_DEFINE_INT32(CA_ROTOR3_TILT, 0); /** - * UAVCAN Servo 6 Minimum Value + * Rotor 4 tilt assignment * - * Minimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN6, 0); +PARAM_DEFINE_INT32(CA_ROTOR4_TILT, 0); /** - * UAVCAN Servo 7 Minimum Value + * Rotor 5 tilt assignment * - * Minimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN7, 0); +PARAM_DEFINE_INT32(CA_ROTOR5_TILT, 0); /** - * UAVCAN Servo 8 Minimum Value + * Rotor 6 tilt assignment * - * Minimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MIN8, 0); +PARAM_DEFINE_INT32(CA_ROTOR6_TILT, 0); /** - * UAVCAN Servo 1 Maximum Value + * Rotor 7 tilt assignment * - * Maxmimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX1, 1000); +PARAM_DEFINE_INT32(CA_ROTOR7_TILT, 0); /** - * UAVCAN Servo 2 Maximum Value + * Rotor 8 tilt assignment * - * Maxmimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX2, 1000); +PARAM_DEFINE_INT32(CA_ROTOR8_TILT, 0); /** - * UAVCAN Servo 3 Maximum Value + * Rotor 9 tilt assignment * - * Maxmimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX3, 1000); +PARAM_DEFINE_INT32(CA_ROTOR9_TILT, 0); /** - * UAVCAN Servo 4 Maximum Value + * Rotor 10 tilt assignment * - * Maxmimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX4, 1000); +PARAM_DEFINE_INT32(CA_ROTOR10_TILT, 0); /** - * UAVCAN Servo 5 Maximum Value + * Rotor 11 tilt assignment * - * Maxmimum output value (when not disarmed). - * + * If not set to None, this motor is tilted by the configured tilt servo. * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @group Geometry + * @value 0 None + * @value 1 Tilt 1 + * @value 2 Tilt 2 + * @value 3 Tilt 3 + * @value 4 Tilt 4 */ -PARAM_DEFINE_INT32(UAVCAN_SV_MAX5, 1000); +PARAM_DEFINE_INT32(CA_ROTOR11_TILT, 0); /** - * UAVCAN Servo 6 Maximum Value + * Total number of Control Surfaces * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @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_INT32(UAVCAN_SV_MAX6, 1000); +PARAM_DEFINE_INT32(CA_SV_CS_COUNT, 0); /** - * UAVCAN Servo 7 Maximum Value + * Control Surface 0 type * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @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(UAVCAN_SV_MAX7, 1000); +PARAM_DEFINE_INT32(CA_SV_CS0_TYPE, 0); /** - * UAVCAN Servo 8 Maximum Value + * Control Surface 1 type * - * Maxmimum output value (when not disarmed). * * - * @group Actuator Outputs - * @min 0 - * @max 1000 + * @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(UAVCAN_SV_MAX8, 1000); +PARAM_DEFINE_INT32(CA_SV_CS1_TYPE, 0); /** - * UAVCAN Servo 1 Failsafe Value + * Control Surface 2 type * - * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @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(UAVCAN_SV_FAIL1, -1); +PARAM_DEFINE_INT32(CA_SV_CS2_TYPE, 0); /** - * UAVCAN Servo 2 Failsafe Value + * Control Surface 3 type * - * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @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(UAVCAN_SV_FAIL2, -1); +PARAM_DEFINE_INT32(CA_SV_CS3_TYPE, 0); /** - * UAVCAN Servo 3 Failsafe Value + * Control Surface 4 type * - * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @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(UAVCAN_SV_FAIL3, -1); +PARAM_DEFINE_INT32(CA_SV_CS4_TYPE, 0); /** - * UAVCAN Servo 4 Failsafe Value + * Control Surface 5 type * - * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @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(UAVCAN_SV_FAIL4, -1); +PARAM_DEFINE_INT32(CA_SV_CS5_TYPE, 0); /** - * UAVCAN Servo 5 Failsafe Value + * Control Surface 6 type * - * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @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(UAVCAN_SV_FAIL5, -1); +PARAM_DEFINE_INT32(CA_SV_CS6_TYPE, 0); /** - * UAVCAN Servo 6 Failsafe Value + * Control Surface 7 type * - * 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 + * @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(UAVCAN_SV_FAIL6, -1); +PARAM_DEFINE_INT32(CA_SV_CS7_TYPE, 0); /** - * UAVCAN Servo 7 Failsafe Value + * Control Surface 0 roll torque scaling * - * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL7, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_R, 0.0); /** - * UAVCAN Servo 8 Failsafe Value + * Control Surface 1 roll torque scaling * - * 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 Actuator Outputs - * @min -1 - * @max 1000 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(UAVCAN_SV_FAIL8, -1); +PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_R, 0.0); /** - * Reverse Output Range for UAVCAN + * Control Surface 2 roll torque scaling * - * 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 - * @min 0 - * @max 255 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(UAVCAN_EC_REV, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_R, 0.0); /** - * Reverse Output Range for UAVCAN + * Control Surface 3 roll torque scaling * - * 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 - * @min 0 - * @max 255 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(UAVCAN_SV_REV, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_R, 0.0); /** - * Enable Gripper actuation in Payload Deliverer + * Control Surface 4 roll torque scaling * * * - * @group Payload Deliverer - * @boolean - * @reboot_required True + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(PD_GRIPPER_EN, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_R, 0.0); /** - * Type of Gripper (Servo, etc.) + * Control Surface 5 roll torque scaling * * * - * @group Payload Deliverer - * @value -1 Undefined - * @value 0 Servo - * @min -1 - * @max 0 + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_INT32(PD_GRIPPER_TYPE, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_R, 0.0); /** - * Timeout for successful gripper actuation acknowledgement + * Control Surface 6 roll torque scaling * - * 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 Payload Deliverer - * @min 0 - * @unit s + * @group Geometry + * @decimal 2 */ -PARAM_DEFINE_FLOAT(PD_GRIPPER_TO, 3); +PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_R, 0.0); /** - * Airframe selection + * Control Surface 7 roll torque scaling * - * 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 + * @decimal 2 */ -PARAM_DEFINE_INT32(CA_AIRFRAME, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_R, 0.0); /** - * Control allocation method + * Control Surface 0 pitch torque scaling * - * 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 + * @decimal 2 */ -PARAM_DEFINE_INT32(CA_METHOD, 2); +PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_P, 0.0); /** - * Bidirectional/Reversible motors + * Control Surface 1 pitch torque scaling * - * 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 + * @decimal 2 */ -PARAM_DEFINE_INT32(CA_R_REV, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_P, 0.0); /** - * Motor 0 slew rate limit + * Control Surface 2 pitch torque scaling * - * 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_R0_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_P, 0.0); /** - * Motor 1 slew rate limit + * Control Surface 3 pitch torque scaling * - * 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_R1_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_P, 0.0); /** - * Motor 2 slew rate limit + * Control Surface 4 pitch torque scaling * - * 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_R2_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_P, 0.0); /** - * Motor 3 slew rate limit + * Control Surface 5 pitch torque scaling * - * 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_R3_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_P, 0.0); /** - * Motor 4 slew rate limit + * Control Surface 6 pitch torque scaling * - * 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_R4_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_P, 0.0); /** - * Motor 5 slew rate limit + * Control Surface 7 pitch torque scaling * - * 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_R5_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_P, 0.0); /** - * Motor 6 slew rate limit + * Control Surface 0 yaw torque scaling * - * 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_R6_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_Y, 0.0); /** - * Motor 7 slew rate limit + * Control Surface 1 yaw torque scaling * - * 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_R7_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_Y, 0.0); /** - * Motor 8 slew rate limit + * Control Surface 2 yaw torque scaling * - * 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_R8_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_Y, 0.0); /** - * Motor 9 slew rate limit + * Control Surface 3 yaw torque scaling * - * 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_R9_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_Y, 0.0); /** - * Motor 10 slew rate limit + * Control Surface 4 yaw torque scaling * - * 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_R10_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_Y, 0.0); /** - * Motor 11 slew rate limit + * Control Surface 5 yaw torque scaling * - * 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_R11_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_Y, 0.0); /** - * Servo 0 slew rate limit + * Control Surface 6 yaw torque scaling * - * 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_SV0_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_Y, 0.0); /** - * Servo 1 slew rate limit + * Control Surface 7 yaw torque scaling * - * 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_SV1_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_Y, 0.0); /** - * Servo 2 slew rate limit + * Control Surface 0 trim * - * 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. - * + * Can be used to add an offset to the servo control. * * @group Geometry * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_SV2_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS0_TRIM, 0.0); /** - * 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. - * + * Control Surface 1 trim + * + * Can be used to add an offset to the servo control. * * @group Geometry * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_SV3_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_TRIM, 0.0); /** - * Servo 4 slew rate limit + * Control Surface 2 trim * - * 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. - * + * Can be used to add an offset to the servo control. * * @group Geometry * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_SV4_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_TRIM, 0.0); /** - * Servo 5 slew rate limit + * Control Surface 3 trim * - * 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. - * + * Can be used to add an offset to the servo control. * * @group Geometry * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_SV5_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_TRIM, 0.0); /** - * Servo 6 slew rate limit + * Control Surface 4 trim * - * 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. - * + * Can be used to add an offset to the servo control. * * @group Geometry * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_SV6_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_TRIM, 0.0); /** - * Servo 7 slew rate limit + * Control Surface 5 trim * - * 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. - * + * Can be used to add an offset to the servo control. * * @group Geometry * @decimal 2 - * @increment 0.05 - * @min 0 - * @max 10 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_SV7_SLEW, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_TRIM, 0.0); /** - * Total number of rotors + * Control Surface 6 trim * - * + * Can be used to add an offset to the servo control. * * @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 + * @decimal 2 + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_INT32(CA_ROTOR_COUNT, 0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_TRIM, 0.0); /** - * Position of rotor 0 along X body axis + * Control Surface 7 trim * - * + * Can be used to add an offset to the servo control. * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_TRIM, 0.0); /** - * Position of rotor 1 along X body axis + * Control Surface 0 configuration as flap * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS0_FLAP, 0); /** - * Position of rotor 2 along X body axis + * Control Surface 1 configuration as flap * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_FLAP, 0); /** - * Position of rotor 3 along X body axis + * Control Surface 2 configuration as flap * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_FLAP, 0); /** - * Position of rotor 4 along X body axis + * Control Surface 3 configuration as flap * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_FLAP, 0); /** - * Position of rotor 5 along X body axis + * Control Surface 4 configuration as flap * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_FLAP, 0); /** - * Position of rotor 6 along X body axis + * Control Surface 5 configuration as flap * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_FLAP, 0); /** - * Position of rotor 7 along X body axis + * Control Surface 6 configuration as flap * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_FLAP, 0); /** - * Position of rotor 8 along X body axis + * Control Surface 7 configuration as flap * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_FLAP, 0); /** - * Position of rotor 9 along X body axis + * Control Surface 0 configuration as spoiler * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS0_SPOIL, 0); /** - * Position of rotor 10 along X body axis + * Control Surface 1 configuration as spoiler * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS1_SPOIL, 0); /** - * Position of rotor 11 along X body axis + * Control Surface 2 configuration as spoiler * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_PX, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS2_SPOIL, 0); /** - * Position of rotor 0 along Y body axis + * Control Surface 3 configuration as spoiler * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_PY, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS3_SPOIL, 0); /** - * Position of rotor 1 along Y body axis + * Control Surface 4 configuration as spoiler * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_PY, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS4_SPOIL, 0); /** - * Position of rotor 2 along Y body axis + * Control Surface 5 configuration as spoiler * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_PY, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS5_SPOIL, 0); /** - * Position of rotor 3 along Y body axis + * Control Surface 6 configuration as spoiler * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_PY, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS6_SPOIL, 0); /** - * Position of rotor 4 along Y body axis + * Control Surface 7 configuration as spoiler * * * * @group Geometry * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @min -1.0 + * @max 1.0 */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_PY, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_CS7_SPOIL, 0); /** - * Position of rotor 5 along Y body axis + * Total number of Tilt Servos * * * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 0 + * @value 1 1 + * @value 2 2 + * @value 3 3 + * @value 4 4 */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_PY, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL_COUNT, 0); /** - * Position of rotor 6 along Y body axis + * Tilt 0 is used for control * - * + * Define if this servo is used for additional control. * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 None + * @value 1 Yaw + * @value 2 Pitch + * @value 3 Yaw and Pitch */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_PY, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL0_CT, 1); /** - * Position of rotor 7 along Y body axis + * Tilt 1 is used for control * - * + * Define if this servo is used for additional control. * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 None + * @value 1 Yaw + * @value 2 Pitch + * @value 3 Yaw and Pitch */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_PY, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL1_CT, 1); /** - * Position of rotor 8 along Y body axis + * Tilt 2 is used for control * - * + * Define if this servo is used for additional control. * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 None + * @value 1 Yaw + * @value 2 Pitch + * @value 3 Yaw and Pitch */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_PY, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL2_CT, 1); /** - * Position of rotor 9 along Y body axis + * Tilt 3 is used for control * - * + * Define if this servo is used for additional control. * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 None + * @value 1 Yaw + * @value 2 Pitch + * @value 3 Yaw and Pitch */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_PY, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL3_CT, 1); /** - * Position of rotor 10 along Y body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_PY, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL0_MINA, 0.0); /** - * Position of rotor 11 along Y body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_PY, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL1_MINA, 0.0); /** - * Position of rotor 0 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_PZ, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL2_MINA, 0.0); /** - * Position of rotor 1 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_PZ, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL3_MINA, 0.0); /** - * Position of rotor 2 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_PZ, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL0_MAXA, 90.0); /** - * Position of rotor 3 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_PZ, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL1_MAXA, 90.0); /** - * Position of rotor 4 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_PZ, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL2_MAXA, 90.0); /** - * Position of rotor 5 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @min -90.0 + * @max 90.0 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_PZ, 0.0); +PARAM_DEFINE_FLOAT(CA_SV_TL3_MAXA, 90.0); /** - * Position of rotor 6 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 Towards Front + * @value 90 Towards Right + * @min 0 + * @max 359 */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_PZ, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL0_TD, 0); /** - * Position of rotor 7 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 Towards Front + * @value 90 Towards Right + * @min 0 + * @max 359 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_PZ, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL1_TD, 0); /** - * Position of rotor 8 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 Towards Front + * @value 90 Towards Right + * @min 0 + * @max 359 */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_PZ, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL2_TD, 0); /** - * Position of rotor 9 along Z body axis + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 0 Towards Front + * @value 90 Towards Right + * @min 0 + * @max 359 */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_PZ, 0.0); +PARAM_DEFINE_INT32(CA_SV_TL3_TD, 0); /** - * Position of rotor 10 along Z body axis + * Number of swash plates servos * * * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @value 3 3 + * @value 4 4 */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_PZ, 0.0); +PARAM_DEFINE_INT32(CA_SP0_COUNT, 3); /** - * Position of rotor 11 along Z body axis + * Angle for swash plate servo 0 * + * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). * * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 - * @unit m + * @decimal 0 + * @increment 10 + * @min 0 + * @max 360 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_PZ, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ANG0, 0); /** - * Axis of rotor 0 thrust vector, X body axis component + * Angle for swash plate servo 1 * - * Only the direction is considered (the vector is normalized). + * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). + * * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @decimal 0 + * @increment 10 + * @min 0 + * @max 360 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ANG1, 140); /** - * Axis of rotor 1 thrust vector, X body axis component + * Angle for swash plate servo 2 * - * Only the direction is considered (the vector is normalized). + * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). + * * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @decimal 0 + * @increment 10 + * @min 0 + * @max 360 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ANG2, 220); /** - * Axis of rotor 2 thrust vector, X body axis component + * Angle for swash plate servo 3 * - * Only the direction is considered (the vector is normalized). + * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). + * * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @decimal 0 + * @increment 10 + * @min 0 + * @max 360 + * @unit deg */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ANG3, 0); /** - * Axis of rotor 3 thrust vector, X body axis component + * Arm length for swash plate servo 0 * - * Only the direction is considered (the vector is normalized). + * This is relative to the other arm lengths. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ARM_L0, 1.0); /** - * Axis of rotor 4 thrust vector, X body axis component + * Arm length for swash plate servo 1 * - * Only the direction is considered (the vector is normalized). + * This is relative to the other arm lengths. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ARM_L1, 1.0); /** - * Axis of rotor 5 thrust vector, X body axis component + * Arm length for swash plate servo 2 * - * Only the direction is considered (the vector is normalized). + * This is relative to the other arm lengths. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ARM_L2, 1.0); /** - * Axis of rotor 6 thrust vector, X body axis component + * Arm length for swash plate servo 3 * - * Only the direction is considered (the vector is normalized). + * This is relative to the other arm lengths. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 10 */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_SP0_ARM_L3, 1.0); /** - * Axis of rotor 7 thrust vector, X body axis component + * Throttle curve at position 0 * - * Only the direction is considered (the vector is normalized). + * Defines the output throttle at the interval position 0. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C0, 1); /** - * Axis of rotor 8 thrust vector, X body axis component + * Throttle curve at position 1 * - * Only the direction is considered (the vector is normalized). + * Defines the output throttle at the interval position 1. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C1, 1); /** - * Axis of rotor 9 thrust vector, X body axis component + * Throttle curve at position 2 * - * Only the direction is considered (the vector is normalized). + * Defines the output throttle at the interval position 2. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C2, 1); /** - * Axis of rotor 10 thrust vector, X body axis component + * Throttle curve at position 3 * - * Only the direction is considered (the vector is normalized). + * Defines the output throttle at the interval position 3. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C3, 1); /** - * Axis of rotor 11 thrust vector, X body axis component + * Throttle curve at position 4 * - * Only the direction is considered (the vector is normalized). + * Defines the output throttle at the interval position 4. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min 0 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_AX, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_THR_C4, 1); /** - * Axis of rotor 0 thrust vector, Y body axis component + * Collective pitch curve at position 0 * - * Only the direction is considered (the vector is normalized). + * 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. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_AY, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C0, -0.05); /** - * Axis of rotor 1 thrust vector, Y body axis component + * Collective pitch curve at position 1 * - * Only the direction is considered (the vector is normalized). + * 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. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_AY, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C1, 0.0725); /** - * Axis of rotor 2 thrust vector, Y body axis component + * Collective pitch curve at position 2 * - * Only the direction is considered (the vector is normalized). + * 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. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_AY, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C2, 0.2); /** - * Axis of rotor 3 thrust vector, Y body axis component + * Collective pitch curve at position 3 * - * Only the direction is considered (the vector is normalized). + * 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. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_AY, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C3, 0.325); /** - * Axis of rotor 4 thrust vector, Y body axis component + * Collective pitch curve at position 4 * - * Only the direction is considered (the vector is normalized). + * 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. + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min -1 + * @max 1 */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_AY, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C4, 0.45); /** - * Axis of rotor 5 thrust vector, Y body axis component + * Scale for yaw compensation based on collective pitch * - * Only the direction is considered (the vector is normalized). + * 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) + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min -2 + * @max 2 */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_AY, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_YAW_CP_S, 0.0); /** - * Axis of rotor 6 thrust vector, Y body axis component + * Offset for yaw compensation based on collective pitch * - * Only the direction is considered (the vector is normalized). + * 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) + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min -2 + * @max 2 */ -PARAM_DEFINE_FLOAT(CA_ROTOR6_AY, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_YAW_CP_O, 0.0); /** - * Axis of rotor 7 thrust vector, Y body axis component + * Scale for yaw compensation based on throttle * - * Only the direction is considered (the vector is normalized). + * 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 + * * * @group Geometry - * @decimal 2 + * @decimal 3 * @increment 0.1 - * @min -100 - * @max 100 + * @min -2 + * @max 2 */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_AY, 0.0); +PARAM_DEFINE_FLOAT(CA_HELI_YAW_TH_S, 0.0); /** - * Axis of rotor 8 thrust vector, Y body axis component + * Main rotor turns counter-clockwise * - * Only the direction is considered (the vector is normalized). + * 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. + * * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @boolean */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_AY, 0.0); +PARAM_DEFINE_INT32(CA_HELI_YAW_CCW, 0); /** - * Axis of rotor 9 thrust vector, Y body axis component + * Motor failure handling mode * - * Only the direction is considered (the vector is normalized). + * This is used to specify how to handle motor failures + * reported by failure detector. + * * * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @value 0 Ignore + * @value 1 Remove first failed motor from effectiveness */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_AY, 0.0); +PARAM_DEFINE_INT32(CA_FAILURE_MODE, 0); /** - * Axis of rotor 10 thrust vector, Y body axis component + * Empty cell voltage (5C load) * - * Only the direction is considered (the vector is normalized). + * 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 Geometry + * @group Battery Calibration * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @increment 0.01 + * @unit V + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_AY, 0.0); +PARAM_DEFINE_FLOAT(BAT1_V_EMPTY, 3.6); /** - * Axis of rotor 11 thrust vector, Y body axis component + * Empty cell voltage (5C load) * - * Only the direction is considered (the vector is normalized). + * 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 Geometry + * @group Battery Calibration * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @increment 0.01 + * @unit V + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_AY, 0.0); +PARAM_DEFINE_FLOAT(BAT2_V_EMPTY, 3.6); /** - * Axis of rotor 0 thrust vector, Z body axis component + * Full cell voltage (5C load) * - * Only the direction is considered (the vector is normalized). + * 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 Geometry + * @group Battery Calibration * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @increment 0.01 + * @unit V + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_AZ, -1.0); +PARAM_DEFINE_FLOAT(BAT1_V_CHARGED, 4.05); /** - * Axis of rotor 1 thrust vector, Z body axis component + * Full cell voltage (5C load) * - * Only the direction is considered (the vector is normalized). + * 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 Geometry + * @group Battery Calibration * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @increment 0.01 + * @unit V + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_AZ, -1.0); +PARAM_DEFINE_FLOAT(BAT2_V_CHARGED, 4.05); /** - * Axis of rotor 2 thrust vector, Z body axis component + * Voltage drop per cell on full throttle * - * Only the direction is considered (the vector is normalized). + * 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 Geometry + * @group Battery Calibration * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @increment 0.01 + * @min 0.07 + * @max 0.5 + * @unit V + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_AZ, -1.0); +PARAM_DEFINE_FLOAT(BAT1_V_LOAD_DROP, 0.1); /** - * Axis of rotor 3 thrust vector, Z body axis component + * Voltage drop per cell on full throttle * - * Only the direction is considered (the vector is normalized). + * 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 Geometry + * @group Battery Calibration * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @increment 0.01 + * @min 0.07 + * @max 0.5 + * @unit V + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_AZ, -1.0); +PARAM_DEFINE_FLOAT(BAT2_V_LOAD_DROP, 0.1); /** - * Axis of rotor 4 thrust vector, Z body axis component + * Explicitly defines the per cell internal resistance for battery 1 * - * Only the direction is considered (the vector is normalized). + * If non-negative, then this will be used in place of + * BAT1_V_LOAD_DROP for all calculations. + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Battery Calibration + * @decimal 4 + * @increment 0.0005 + * @min -1.0 + * @max 0.2 + * @unit Ohm + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR4_AZ, -1.0); +PARAM_DEFINE_FLOAT(BAT1_R_INTERNAL, 0.005); /** - * Axis of rotor 5 thrust vector, Z body axis component + * Explicitly defines the per cell internal resistance for battery 2 * - * Only the direction is considered (the vector is normalized). + * If non-negative, then this will be used in place of + * BAT2_V_LOAD_DROP for all calculations. + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Battery Calibration + * @decimal 4 + * @increment 0.0005 + * @min -1.0 + * @max 0.2 + * @unit Ohm + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_AZ, -1.0); +PARAM_DEFINE_FLOAT(BAT2_R_INTERNAL, 0.005); /** - * Axis of rotor 6 thrust vector, Z body axis component + * Number of cells for battery 1. * - * Only the direction is considered (the vector is normalized). + * Defines the number of cells the attached battery consists of. + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @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_FLOAT(CA_ROTOR6_AZ, -1.0); +PARAM_DEFINE_INT32(BAT1_N_CELLS, 0); /** - * Axis of rotor 7 thrust vector, Z body axis component + * Number of cells for battery 2. * - * Only the direction is considered (the vector is normalized). + * Defines the number of cells the attached battery consists of. + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @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_FLOAT(CA_ROTOR7_AZ, -1.0); +PARAM_DEFINE_INT32(BAT2_N_CELLS, 0); /** - * Axis of rotor 8 thrust vector, Z body axis component + * Battery 1 capacity. * - * Only the direction is considered (the vector is normalized). + * Defines the capacity of battery 1 in mAh. + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Battery Calibration + * @decimal 0 + * @increment 50 + * @min -1.0 + * @max 100000 + * @unit mAh + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR8_AZ, -1.0); +PARAM_DEFINE_FLOAT(BAT1_CAPACITY, -1.0); /** - * Axis of rotor 9 thrust vector, Z body axis component + * Battery 2 capacity. * - * Only the direction is considered (the vector is normalized). + * Defines the capacity of battery 2 in mAh. + * * - * @group Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Battery Calibration + * @decimal 0 + * @increment 50 + * @min -1.0 + * @max 100000 + * @unit mAh + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_AZ, -1.0); +PARAM_DEFINE_FLOAT(BAT2_CAPACITY, -1.0); /** - * Axis of rotor 10 thrust vector, Z body axis component + * Battery 1 monitoring source. * - * Only the direction is considered (the vector is normalized). + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Battery Calibration + * @value -1 Disabled + * @value 0 Power Module + * @value 1 External + * @value 2 ESCs + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR10_AZ, -1.0); +PARAM_DEFINE_INT32(BAT1_SOURCE, 0); /** - * Axis of rotor 11 thrust vector, Z body axis component + * Battery 2 monitoring source. * - * Only the direction is considered (the vector is normalized). + * 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 Geometry - * @decimal 2 - * @increment 0.1 - * @min -100 - * @max 100 + * @group Battery Calibration + * @value -1 Disabled + * @value 0 Power Module + * @value 1 External + * @value 2 ESCs + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_AZ, -1.0); +PARAM_DEFINE_INT32(BAT2_SOURCE, -1); /** - * Thrust coefficient of rotor 0 + * uXRCE-DDS domain ID * - * 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. - * + * uXRCE-DDS domain ID * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 + * @group UXRCE-DDS Client + * @category System + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR0_CT, 6.5); +PARAM_DEFINE_INT32(UXRCE_DDS_DOM_ID, 0); /** - * Thrust coefficient of rotor 1 + * uXRCE-DDS Session key * - * 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. + * uXRCE-DDS key, must be different from zero. + * In a single agent - multi client configuration, each client + * must have a unique session key. * * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 + * @group UXRCE-DDS Client + * @category System + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR1_CT, 6.5); +PARAM_DEFINE_INT32(UXRCE_DDS_KEY, 1); /** - * Thrust coefficient of rotor 2 + * uXRCE-DDS UDP Port * - * 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. + * If ethernet enabled and selected as configuration for uXRCE-DDS, + * selected udp port will be set and used. * * - * @group Geometry - * @decimal 1 - * @increment 1 + * @group UXRCE-DDS Client * @min 0 - * @max 100 + * @max 65535 + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR2_CT, 6.5); +PARAM_DEFINE_INT32(UXRCE_DDS_PRT, 8888); /** - * Thrust coefficient of rotor 3 + * uXRCE-DDS Agent IP address * - * 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. + * If ethernet enabled and selected as configuration for uXRCE-DDS, + * selected Agent IP address will be set and used. + * Decimal dot notation is not supported. IP address must be provided + * in int32 format. For example, 192.168.1.2 is mapped to -1062731518; + * 127.0.0.1 is mapped to 2130706433. * * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 + * @group UXRCE-DDS Client + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_ROTOR3_CT, 6.5); +PARAM_DEFINE_INT32(UXRCE_DDS_AG_IP, 2130706433); /** - * Thrust coefficient of rotor 4 + * SIM_GZ ESC 1 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 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 * * - * @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_ROTOR4_CT, 6.5); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC1, 0); /** - * Thrust coefficient of rotor 5 + * SIM_GZ ESC 2 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 SIM_GZ ESC 2. * - * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 - */ -PARAM_DEFINE_FLOAT(CA_ROTOR5_CT, 6.5); - -/** - * 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. + * 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_ROTOR6_CT, 6.5); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC2, 0); /** - * Thrust coefficient of rotor 7 + * SIM_GZ ESC 3 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 SIM_GZ ESC 3. * - * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 - */ -PARAM_DEFINE_FLOAT(CA_ROTOR7_CT, 6.5); - -/** - * 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. + * 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_ROTOR8_CT, 6.5); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC3, 0); /** - * Thrust coefficient of rotor 9 + * SIM_GZ ESC 4 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 SIM_GZ ESC 4. * - * - * @group Geometry - * @decimal 1 - * @increment 1 - * @min 0 - * @max 100 - */ -PARAM_DEFINE_FLOAT(CA_ROTOR9_CT, 6.5); - -/** - * 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. + * 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_ROTOR10_CT, 6.5); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC4, 0); /** - * Thrust coefficient of rotor 11 + * SIM_GZ ESC 5 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 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 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_ROTOR11_CT, 6.5); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC5, 0); /** - * Moment coefficient of rotor 0 + * SIM_GZ ESC 6 Output Function * - * The moment coefficient if defined as Torque = KM * Thrust. + * Select what should be output on SIM_GZ ESC 6. * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * 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 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @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_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC6, 0); /** - * Moment coefficient of rotor 1 + * SIM_GZ ESC 7 Output Function * - * The moment coefficient if defined as Torque = KM * Thrust. + * Select what should be output on SIM_GZ ESC 7. * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * 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 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @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_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC7, 0); /** - * Moment coefficient of rotor 2 + * SIM_GZ ESC 8 Output Function * - * The moment coefficient if defined as Torque = KM * Thrust. + * Select what should be output on SIM_GZ ESC 8. * - * Use a positive value for a rotor with CCW rotation. - * Use a negative value for a rotor with CW rotation. + * 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 3 - * @increment 0.01 - * @min -1 - * @max 1 + * @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_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_FUNC8, 0); /** - * Moment coefficient of rotor 3 + * SIM_GZ ESC 1 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_ROTOR3_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS1, 0); /** - * Moment coefficient of rotor 4 + * SIM_GZ ESC 2 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_ROTOR4_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS2, 0); /** - * Moment coefficient of rotor 5 + * SIM_GZ ESC 3 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_ROTOR5_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS3, 0); /** - * Moment coefficient of rotor 6 + * SIM_GZ ESC 4 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_ROTOR6_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS4, 0); /** - * Moment coefficient of rotor 7 + * SIM_GZ ESC 5 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_ROTOR7_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS5, 0); /** - * Moment coefficient of rotor 8 + * SIM_GZ ESC 6 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_ROTOR8_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS6, 0); /** - * Moment coefficient of rotor 9 + * SIM_GZ ESC 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_ROTOR9_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS7, 0); /** - * Moment coefficient of rotor 10 + * SIM_GZ ESC 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_ROTOR10_KM, 0.05); +PARAM_DEFINE_INT32(SIM_GZ_EC_DIS8, 0); /** - * Moment coefficient of rotor 11 + * SIM_GZ ESC 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 - */ -PARAM_DEFINE_FLOAT(CA_ROTOR11_KM, 0.05); - -/** - * Rotor 0 tilt assignment - * - * If not set to None, this motor is tilted by the configured tilt servo. - * - * @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(SIM_GZ_EC_MIN1, 0); /** - * Rotor 1 tilt assignment + * SIM_GZ ESC 2 Minimum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Minimum 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(SIM_GZ_EC_MIN2, 0); /** - * Rotor 2 tilt assignment + * SIM_GZ ESC 3 Minimum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Minimum 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(SIM_GZ_EC_MIN3, 0); /** - * Rotor 3 tilt assignment + * SIM_GZ ESC 4 Minimum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Minimum 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(SIM_GZ_EC_MIN4, 0); /** - * Rotor 4 tilt assignment + * SIM_GZ ESC 5 Minimum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Minimum 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(SIM_GZ_EC_MIN5, 0); /** - * Rotor 5 tilt assignment + * SIM_GZ ESC 6 Minimum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Minimum 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(SIM_GZ_EC_MIN6, 0); /** - * Rotor 6 tilt assignment + * SIM_GZ ESC 7 Minimum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Minimum 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_ROTOR6_TILT, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN7, 0); /** - * Rotor 7 tilt assignment + * SIM_GZ ESC 8 Minimum Value * - * If not set to None, this motor is tilted by the configured tilt servo. + * Minimum 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_ROTOR7_TILT, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MIN8, 0); /** - * Rotor 8 tilt assignment + * SIM_GZ ESC 1 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_ROTOR8_TILT, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX1, 1000); /** - * Rotor 9 tilt assignment + * SIM_GZ ESC 2 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_ROTOR9_TILT, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX2, 1000); /** - * Rotor 10 tilt assignment + * SIM_GZ ESC 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_ROTOR10_TILT, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX3, 1000); /** - * Rotor 11 tilt assignment + * SIM_GZ ESC 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_ROTOR11_TILT, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX4, 1000); /** - * Total number of Control Surfaces + * SIM_GZ ESC 5 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @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 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_CS_COUNT, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX5, 1000); /** - * Control Surface 0 type + * SIM_GZ ESC 6 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @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 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_CS0_TYPE, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX6, 1000); /** - * Control Surface 1 type + * SIM_GZ ESC 7 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @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 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_CS1_TYPE, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX7, 1000); /** - * Control Surface 2 type + * SIM_GZ ESC 8 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @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 0 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_CS2_TYPE, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_MAX8, 1000); /** - * Control Surface 3 type + * 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 SIM_GZ_EC_FUNC1). * * - * @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_CS3_TYPE, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL1, -1); /** - * Control Surface 4 type + * SIM_GZ ESC 2 Failsafe Value * + * This is the output value that is set when in failsafe mode. * - * - * @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 + * When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC2). + * + * + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_CS4_TYPE, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL2, -1); /** - * Control Surface 5 type + * 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 SIM_GZ_EC_FUNC3). * * - * @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_CS5_TYPE, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL3, -1); /** - * Control Surface 6 type + * 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 SIM_GZ_EC_FUNC4). * * - * @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_CS6_TYPE, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL4, -1); /** - * Control Surface 7 type + * 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 SIM_GZ_EC_FUNC5). * * - * @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_CS7_TYPE, 0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL5, -1); /** - * Control Surface 0 roll torque scaling + * 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 SIM_GZ_EC_FUNC6). * * - * @group Geometry - * @decimal 2 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_R, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL6, -1); /** - * Control Surface 1 roll torque scaling + * 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 SIM_GZ_EC_FUNC7). * * - * @group Geometry - * @decimal 2 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_R, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL7, -1); /** - * Control Surface 2 roll torque scaling + * 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 SIM_GZ_EC_FUNC8). * * - * @group Geometry - * @decimal 2 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_R, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_EC_FAIL8, -1); /** - * Control Surface 3 roll torque scaling + * SIM_GZ Servo 1 Output Function * + * 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 Geometry - * @decimal 2 + * @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_SV_CS3_TRQ_R, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC1, 0); /** - * Control Surface 4 roll torque scaling + * SIM_GZ Servo 2 Output Function * + * 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 Geometry - * @decimal 2 + * @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_SV_CS4_TRQ_R, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC2, 0); /** - * Control Surface 5 roll torque scaling + * SIM_GZ Servo 3 Output Function * + * Select what should be output on SIM_GZ Servo 3. * - * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_R, 0.0); - -/** - * Control Surface 6 roll torque scaling - * + * 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 + * @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_SV_CS6_TRQ_R, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC3, 0); /** - * Control Surface 7 roll torque scaling + * 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 Geometry - * @decimal 2 + * @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_SV_CS7_TRQ_R, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC4, 0); /** - * Control Surface 0 pitch torque scaling + * 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 Geometry - * @decimal 2 + * @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_SV_CS0_TRQ_P, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC5, 0); /** - * Control Surface 1 pitch torque scaling + * 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 Geometry - * @decimal 2 + * @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_SV_CS1_TRQ_P, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC6, 0); /** - * Control Surface 2 pitch torque scaling + * SIM_GZ Servo 7 Output Function * + * Select what should be output on SIM_GZ Servo 7. * - * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_P, 0.0); - -/** - * Control Surface 3 pitch torque scaling - * + * 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 + * @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_SV_CS3_TRQ_P, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC7, 0); /** - * Control Surface 4 pitch torque scaling + * SIM_GZ Servo 8 Output Function * + * Select what should be output on SIM_GZ Servo 8. * - * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_P, 0.0); - -/** - * Control Surface 5 pitch torque scaling - * + * 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 + * @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_SV_CS5_TRQ_P, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FUNC8, 0); /** - * Control Surface 6 pitch torque scaling + * SIM_GZ Servo 1 Disarmed Value * + * This is the output value that is set when not armed. * - * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_P, 0.0); - -/** - * Control Surface 7 pitch torque scaling - * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_P, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS1, 500); /** - * Control Surface 0 yaw torque scaling + * SIM_GZ Servo 2 Disarmed Value * + * This is the output value that is set when not armed. * - * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_TRQ_Y, 0.0); - -/** - * Control Surface 1 yaw torque scaling - * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_TRQ_Y, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS2, 500); /** - * Control Surface 2 yaw torque scaling + * SIM_GZ Servo 3 Disarmed Value * + * This is the output value that is set when not armed. * - * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_TRQ_Y, 0.0); - -/** - * Control Surface 3 yaw torque scaling - * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_TRQ_Y, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS3, 500); /** - * Control Surface 4 yaw torque scaling + * SIM_GZ Servo 4 Disarmed Value * + * This is the output value that is set when not armed. * - * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_TRQ_Y, 0.0); - -/** - * Control Surface 5 yaw torque scaling - * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 2 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_TRQ_Y, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS4, 500); /** - * Control Surface 6 yaw torque scaling + * SIM_GZ Servo 5 Disarmed Value * + * This is the output value that is set when not armed. * - * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_TRQ_Y, 0.0); - -/** - * Control Surface 7 yaw torque scaling - * + * Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. * * - * @group Geometry - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_TRQ_Y, 0.0); - -/** - * Control Surface 0 trim - * - * Can be used to add an offset to the servo control. - * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_TRIM, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS5, 500); /** - * Control Surface 1 trim + * SIM_GZ Servo 6 Disarmed Value * - * Can be used to add an offset to the servo control. + * 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 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_TRIM, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS6, 500); /** - * Control Surface 2 trim + * SIM_GZ Servo 7 Disarmed Value * - * Can be used to add an offset to the servo control. + * 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 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_TRIM, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS7, 500); /** - * Control Surface 3 trim + * SIM_GZ Servo 8 Disarmed Value * - * Can be used to add an offset to the servo control. + * 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 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_TRIM, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_DIS8, 500); /** - * Control Surface 4 trim + * SIM_GZ Servo 1 Minimum Value * - * Can be used to add an offset to the servo control. + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_TRIM, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN1, 0); /** - * Control Surface 5 trim + * SIM_GZ Servo 2 Minimum Value * - * Can be used to add an offset to the servo control. + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_TRIM, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN2, 0); /** - * Control Surface 6 trim + * SIM_GZ Servo 3 Minimum Value * - * Can be used to add an offset to the servo control. + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_TRIM, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN3, 0); /** - * Control Surface 7 trim + * SIM_GZ Servo 4 Minimum Value * - * Can be used to add an offset to the servo control. + * Minimum output value (when not disarmed). + * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_TRIM, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN4, 0); /** - * Control Surface 0 configuration as flap + * SIM_GZ Servo 5 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_FLAP, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN5, 0); /** - * Control Surface 1 configuration as flap + * SIM_GZ Servo 6 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_FLAP, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN6, 0); /** - * Control Surface 2 configuration as flap + * SIM_GZ Servo 7 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_FLAP, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN7, 0); /** - * Control Surface 3 configuration as flap + * SIM_GZ Servo 8 Minimum Value * + * Minimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_FLAP, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MIN8, 0); /** - * Control Surface 4 configuration as flap + * SIM_GZ Servo 1 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS4_FLAP, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX1, 1000); /** - * Control Surface 5 configuration as flap + * SIM_GZ Servo 2 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_FLAP, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX2, 1000); /** - * Control Surface 6 configuration as flap + * SIM_GZ Servo 3 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_FLAP, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX3, 1000); /** - * Control Surface 7 configuration as flap + * SIM_GZ Servo 4 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_FLAP, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX4, 1000); /** - * Control Surface 0 configuration as spoiler + * SIM_GZ Servo 5 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS0_SPOIL, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX5, 1000); /** - * Control Surface 1 configuration as spoiler + * SIM_GZ Servo 6 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS1_SPOIL, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX6, 1000); /** - * Control Surface 2 configuration as spoiler + * SIM_GZ Servo 7 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS2_SPOIL, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX7, 1000); /** - * Control Surface 3 configuration as spoiler + * SIM_GZ Servo 8 Maximum Value * + * Maxmimum output value (when not disarmed). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min 0 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS3_SPOIL, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_MAX8, 1000); /** - * Control Surface 4 configuration as spoiler + * SIM_GZ Servo 1 Failsafe Value * + * This is the output value that is set when in failsafe mode. * - * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * 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_FLOAT(CA_SV_CS4_SPOIL, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL1, -1); /** - * Control Surface 5 configuration as spoiler + * 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 SIM_GZ_SV_FUNC2). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS5_SPOIL, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL2, -1); /** - * Control Surface 6 configuration as spoiler + * 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 SIM_GZ_SV_FUNC3). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS6_SPOIL, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL3, -1); /** - * Control Surface 7 configuration as spoiler + * 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 SIM_GZ_SV_FUNC4). * * - * @group Geometry - * @decimal 2 - * @min -1.0 - * @max 1.0 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_FLOAT(CA_SV_CS7_SPOIL, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL4, -1); /** - * Total number of Tilt Servos + * 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 SIM_GZ_SV_FUNC5). * * - * @group Geometry - * @value 0 0 - * @value 1 1 - * @value 2 2 - * @value 3 3 - * @value 4 4 + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_TL_COUNT, 0); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL5, -1); /** - * Tilt 0 is used for control + * SIM_GZ Servo 6 Failsafe Value * - * Define if this servo is used for additional control. + * 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 Geometry - * @value 0 None - * @value 1 Yaw - * @value 2 Pitch - * @value 3 Yaw and Pitch + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_TL0_CT, 1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL6, -1); /** - * Tilt 1 is used for control + * SIM_GZ Servo 7 Failsafe Value * - * Define if this servo is used for additional control. + * 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 Geometry - * @value 0 None - * @value 1 Yaw - * @value 2 Pitch - * @value 3 Yaw and Pitch + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_TL1_CT, 1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL7, -1); /** - * Tilt 2 is used for control + * SIM_GZ Servo 8 Failsafe Value * - * Define if this servo is used for additional control. + * 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 Geometry - * @value 0 None - * @value 1 Yaw - * @value 2 Pitch - * @value 3 Yaw and Pitch + * @group Actuator Outputs + * @min -1 + * @max 1000 */ -PARAM_DEFINE_INT32(CA_SV_TL2_CT, 1); +PARAM_DEFINE_INT32(SIM_GZ_SV_FAIL8, -1); /** - * Tilt 3 is used for control + * Reverse Output Range for SIM_GZ * - * Define if this servo is used for additional control. + * Allows to reverse the output range for each channel. + * Note: this is only useful for servos. + * * - * @group Geometry - * @value 0 None - * @value 1 Yaw - * @value 2 Pitch - * @value 3 Yaw and Pitch + * @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 */ -PARAM_DEFINE_INT32(CA_SV_TL3_CT, 1); +PARAM_DEFINE_INT32(SIM_GZ_EC_REV, 0); /** - * Tilt Servo 0 Tilt Angle at Minimum + * Reverse Output Range for SIM_GZ * - * Defines the tilt angle when the servo is at the minimum. - * An angle of zero means upwards. + * Allows to reverse the output range for each channel. + * Note: this is only useful for servos. * * - * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @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 */ -PARAM_DEFINE_FLOAT(CA_SV_TL0_MINA, 0.0); +PARAM_DEFINE_INT32(SIM_GZ_SV_REV, 0); /** - * Tilt Servo 1 Tilt Angle at Minimum + * Enable Gripper actuation in Payload Deliverer * - * 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 + * @group Payload Deliverer + * @boolean + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SV_TL1_MINA, 0.0); +PARAM_DEFINE_INT32(PD_GRIPPER_EN, 0); /** - * Tilt Servo 2 Tilt Angle at Minimum + * Type of Gripper (Servo, etc.) * - * 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 + * @group Payload Deliverer + * @value -1 Undefined + * @value 0 Servo + * @min -1 + * @max 0 */ -PARAM_DEFINE_FLOAT(CA_SV_TL2_MINA, 0.0); +PARAM_DEFINE_INT32(PD_GRIPPER_TYPE, 0); /** - * Tilt Servo 3 Tilt Angle at Minimum + * Timeout for successful gripper actuation acknowledgement * - * Defines the tilt angle when the servo is at the minimum. - * An angle of zero means upwards. + * 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 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @group Payload Deliverer + * @min 0 + * @unit s */ -PARAM_DEFINE_FLOAT(CA_SV_TL3_MINA, 0.0); +PARAM_DEFINE_FLOAT(PD_GRIPPER_TO, 3); /** - * Tilt Servo 0 Tilt Angle at Maximum + * MAVLink Config for instance 0 * - * Defines the tilt angle when the servo is at the maximum. - * An angle of zero means upwards. + * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance * * - * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @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_FLOAT(CA_SV_TL0_MAXA, 90.0); +PARAM_DEFINE_INT32(MAV_0_CONFIG, 0); /** - * Tilt Servo 1 Tilt Angle at Maximum + * MAVLink Config for instance 1 * - * Defines the tilt angle when the servo is at the maximum. - * An angle of zero means upwards. + * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance * * - * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @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_FLOAT(CA_SV_TL1_MAXA, 90.0); +PARAM_DEFINE_INT32(MAV_1_CONFIG, 0); /** - * Tilt Servo 2 Tilt Angle at Maximum + * MAVLink Config for instance 2 * - * Defines the tilt angle when the servo is at the maximum. - * An angle of zero means upwards. + * The MAVLink Config defines device(uart/udp/tcp) used by MAVLink instance * * - * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @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_FLOAT(CA_SV_TL2_MAXA, 90.0); +PARAM_DEFINE_INT32(MAV_2_CONFIG, 0); /** - * Tilt Servo 3 Tilt Angle at Maximum + * MAVLink Mode for instance 0 * - * Defines the tilt angle when the servo is at the maximum. - * An angle of zero means upwards. + * The MAVLink Mode defines the set of streamed messages (for example the + * vehicle's attitude) and their sending rates. * * - * @group Geometry - * @decimal 0 - * @min -90.0 - * @max 90.0 - * @unit deg + * @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_FLOAT(CA_SV_TL3_MAXA, 90.0); +PARAM_DEFINE_INT32(MAV_0_MODE, 0); /** - * Tilt Servo 0 Tilt Direction + * MAVLink Mode for instance 1 * - * 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. + * The MAVLink Mode defines the set of streamed messages (for example the + * vehicle's attitude) and their sending rates. * * - * @group Geometry - * @value 0 Towards Front - * @value 90 Towards Right - * @min 0 - * @max 359 + * @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(CA_SV_TL0_TD, 0); +PARAM_DEFINE_INT32(MAV_1_MODE, 2); /** - * Tilt Servo 1 Tilt Direction + * MAVLink Mode for instance 2 * - * 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. + * The MAVLink Mode defines the set of streamed messages (for example the + * vehicle's attitude) and their sending rates. * * - * @group Geometry - * @value 0 Towards Front - * @value 90 Towards Right - * @min 0 - * @max 359 + * @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(CA_SV_TL1_TD, 0); +PARAM_DEFINE_INT32(MAV_2_MODE, 0); /** - * Tilt Servo 2 Tilt Direction + * Maximum MAVLink sending rate for instance 0 * - * 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. + * 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 Geometry - * @value 0 Towards Front - * @value 90 Towards Right + * @group MAVLink * @min 0 - * @max 359 + * @unit B/s + * @reboot_required True */ -PARAM_DEFINE_INT32(CA_SV_TL2_TD, 0); +PARAM_DEFINE_INT32(MAV_0_RATE, 1200); /** - * Tilt Servo 3 Tilt Direction + * Maximum MAVLink sending rate for instance 1 * - * 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. + * 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 Geometry - * @value 0 Towards Front - * @value 90 Towards Right + * @group MAVLink * @min 0 - * @max 359 + * @unit B/s + * @reboot_required True */ -PARAM_DEFINE_INT32(CA_SV_TL3_TD, 0); +PARAM_DEFINE_INT32(MAV_1_RATE, 0); /** - * Number of swash plates servos + * 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. * - * - * @group Geometry - * @value 3 3 - * @value 4 4 - */ -PARAM_DEFINE_INT32(CA_SP0_COUNT, 3); - -/** - * Angle for swash plate servo 0 - * - * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). + * 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 Geometry - * @decimal 0 - * @increment 10 + * @group MAVLink * @min 0 - * @max 360 - * @unit deg + * @unit B/s + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SP0_ANG0, 0); +PARAM_DEFINE_INT32(MAV_2_RATE, 0); /** - * Angle for swash plate servo 1 + * Enable MAVLink Message forwarding for instance 0 * - * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). + * 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 Geometry - * @decimal 0 - * @increment 10 - * @min 0 - * @max 360 - * @unit deg + * @group MAVLink + * @boolean + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SP0_ANG1, 140); +PARAM_DEFINE_INT32(MAV_0_FORWARD, 1); /** - * Angle for swash plate servo 2 + * Enable MAVLink Message forwarding for instance 1 * - * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). + * 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 Geometry - * @decimal 0 - * @increment 10 - * @min 0 - * @max 360 - * @unit deg + * @group MAVLink + * @boolean + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SP0_ANG2, 220); +PARAM_DEFINE_INT32(MAV_1_FORWARD, 0); /** - * Angle for swash plate servo 3 + * Enable MAVLink Message forwarding for instance 2 * - * The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). + * 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 Geometry - * @decimal 0 - * @increment 10 - * @min 0 - * @max 360 - * @unit deg + * @group MAVLink + * @boolean + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SP0_ANG3, 0); +PARAM_DEFINE_INT32(MAV_2_FORWARD, 0); /** - * Arm length for swash plate servo 0 - * - * This is relative to the other arm lengths. - * + * Enable software throttling of mavlink on instance 0 * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 10 + * 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 */ -PARAM_DEFINE_FLOAT(CA_SP0_ARM_L0, 1.0); +PARAM_DEFINE_INT32(MAV_0_RADIO_CTL, 1); /** - * Arm length for swash plate servo 1 + * Enable software throttling of mavlink on instance 1 * - * This is relative to the other arm lengths. + * 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 Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 10 + * @group MAVLink + * @boolean + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SP0_ARM_L1, 1.0); +PARAM_DEFINE_INT32(MAV_1_RADIO_CTL, 1); /** - * Arm length for swash plate servo 2 + * Enable software throttling of mavlink on instance 2 * - * This is relative to the other arm lengths. + * 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 Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 10 + * @group MAVLink + * @boolean + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SP0_ARM_L2, 1.0); +PARAM_DEFINE_INT32(MAV_2_RADIO_CTL, 1); /** - * Arm length for swash plate servo 3 + * MAVLink Network Port for instance 0 * - * This is relative to the other arm lengths. + * If ethernet enabled and selected as configuration for MAVLink instance 0, + * selected udp port will be set and used in MAVLink instance 0. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 10 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_SP0_ARM_L3, 1.0); +PARAM_DEFINE_INT32(MAV_0_UDP_PRT, 14556); /** - * Throttle curve at position 0 + * MAVLink Network Port for instance 1 * - * Defines the output throttle at the interval position 0. + * If ethernet enabled and selected as configuration for MAVLink instance 1, + * selected udp port will be set and used in MAVLink instance 1. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 1 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C0, 1); +PARAM_DEFINE_INT32(MAV_1_UDP_PRT, 0); /** - * Throttle curve at position 1 + * MAVLink Network Port for instance 2 * - * Defines the output throttle at the interval position 1. + * If ethernet enabled and selected as configuration for MAVLink instance 2, + * selected udp port will be set and used in MAVLink instance 2. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 1 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C1, 1); +PARAM_DEFINE_INT32(MAV_2_UDP_PRT, 0); /** - * Throttle curve at position 2 + * MAVLink Remote IP for instance 0 * - * Defines the output throttle at the interval position 2. + * If ethernet enabled and selected as configuration for MAVLink instance 0, + * selected remote IP will be set and used in MAVLink instance 0. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 1 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C2, 1); +PARAM_DEFINE_INT32(MAV_0_REMOTE_IP, 0); /** - * Throttle curve at position 3 + * MAVLink Remote IP for instance 1 * - * Defines the output throttle at the interval position 3. + * If ethernet enabled and selected as configuration for MAVLink instance 1, + * selected remote IP will be set and used in MAVLink instance 1. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 1 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C3, 1); +PARAM_DEFINE_INT32(MAV_1_REMOTE_IP, 0); /** - * Throttle curve at position 4 + * MAVLink Remote IP for instance 2 * - * Defines the output throttle at the interval position 4. + * If ethernet enabled and selected as configuration for MAVLink instance 2, + * selected remote IP will be set and used in MAVLink instance 2. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min 0 - * @max 1 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_THR_C4, 1); +PARAM_DEFINE_INT32(MAV_2_REMOTE_IP, 0); /** - * Collective pitch curve at position 0 + * MAVLink Remote Port for instance 0 * - * 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. + * If ethernet enabled and selected as configuration for MAVLink instance 0, + * selected remote port will be set and used in MAVLink instance 0. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min -1 - * @max 1 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C0, -0.05); +PARAM_DEFINE_INT32(MAV_0_REMOTE_PRT, 14550); /** - * Collective pitch curve at position 1 + * MAVLink Remote Port for instance 1 * - * 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. + * If ethernet enabled and selected as configuration for MAVLink instance 1, + * selected remote port will be set and used in MAVLink instance 1. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min -1 - * @max 1 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C1, 0.0725); +PARAM_DEFINE_INT32(MAV_1_REMOTE_PRT, 0); /** - * Collective pitch curve at position 2 + * MAVLink Remote Port for instance 2 * - * 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. + * If ethernet enabled and selected as configuration for MAVLink instance 2, + * selected remote port will be set and used in MAVLink instance 2. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min -1 - * @max 1 + * @group MAVLink + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C2, 0.2); +PARAM_DEFINE_INT32(MAV_2_REMOTE_PRT, 0); /** - * Collective pitch curve at position 3 + * Broadcast heartbeats on local network for MAVLink instance 0 * - * 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. + * This allows a ground control station to automatically find the drone + * on the local network. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min -1 - * @max 1 + * @group MAVLink + * @value 0 Never broadcast + * @value 1 Always broadcast + * @value 2 Only multicast */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C3, 0.325); +PARAM_DEFINE_INT32(MAV_0_BROADCAST, 1); /** - * Collective pitch curve at position 4 + * Broadcast heartbeats on local network for MAVLink instance 1 * - * 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. + * This allows a ground control station to automatically find the drone + * on the local network. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min -1 - * @max 1 + * @group MAVLink + * @value 0 Never broadcast + * @value 1 Always broadcast + * @value 2 Only multicast */ -PARAM_DEFINE_FLOAT(CA_HELI_PITCH_C4, 0.45); +PARAM_DEFINE_INT32(MAV_1_BROADCAST, 0); /** - * Scale for yaw compensation based on collective pitch + * Broadcast heartbeats on local network for MAVLink instance 2 * - * 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) + * This allows a ground control station to automatically find the drone + * on the local network. * * - * @group Geometry - * @decimal 3 - * @increment 0.1 - * @min -2 - * @max 2 + * @group MAVLink + * @value 0 Never broadcast + * @value 1 Always broadcast + * @value 2 Only multicast */ -PARAM_DEFINE_FLOAT(CA_HELI_YAW_CP_S, 0.0); +PARAM_DEFINE_INT32(MAV_2_BROADCAST, 0); /** - * Offset for yaw compensation based on collective pitch + * Enable serial flow control for instance 0 * - * 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) + * 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 Geometry - * @decimal 3 - * @increment 0.1 - * @min -2 - * @max 2 + * @group MAVLink + * @value 0 Force off + * @value 1 Force on + * @value 2 Auto-detected + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_YAW_CP_O, 0.0); +PARAM_DEFINE_INT32(MAV_0_FLOW_CTRL, 2); /** - * Scale for yaw compensation based on throttle + * Enable serial flow control for instance 1 * - * 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 + * 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 Geometry - * @decimal 3 - * @increment 0.1 - * @min -2 - * @max 2 + * @group MAVLink + * @value 0 Force off + * @value 1 Force on + * @value 2 Auto-detected + * @reboot_required True */ -PARAM_DEFINE_FLOAT(CA_HELI_YAW_TH_S, 0.0); +PARAM_DEFINE_INT32(MAV_1_FLOW_CTRL, 2); /** - * Main rotor turns counter-clockwise + * Enable serial flow control for instance 2 * - * 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. + * 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 Geometry - * @boolean + * @group MAVLink + * @value 0 Force off + * @value 1 Force on + * @value 2 Auto-detected + * @reboot_required True */ -PARAM_DEFINE_INT32(CA_HELI_YAW_CCW, 0); +PARAM_DEFINE_INT32(MAV_2_FLOW_CTRL, 2); /** - * Motor failure handling mode + * RC input protocol * - * This is used to specify how to handle motor failures - * reported by failure detector. + * Select your RC input protocol or auto to scan. * * - * @group Geometry - * @value 0 Ignore - * @value 1 Remove first failed motor from effectiveness + * @group RC Input + * @value -1 Auto + * @value 0 None + * @value 1 PPM + * @value 2 SBUS + * @value 3 DSM + * @value 4 ST24 + * @value 5 SUMD + * @value 6 CRSF + * @value 7 GHST + * @category System + * @min -1 + * @max 7 */ -PARAM_DEFINE_INT32(CA_FAILURE_MODE, 0); +PARAM_DEFINE_INT32(RC_INPUT_PROTO, -1);