diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index 69569170c890..4807762e6237 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -17,5 +17,8 @@ jobs: with: token: ${{secrets.ACCESS_TOKEN}} + - name: install dependencies + run: pip3 install dataclasses + - name: make clang-tidy-quiet run: make clang-tidy-quiet diff --git a/.github/workflows/mavros_mission_tests.yml b/.github/workflows/mavros_mission_tests.yml index 8401f61b1176..0b191c217ef5 100644 --- a/.github/workflows/mavros_mission_tests.yml +++ b/.github/workflows/mavros_mission_tests.yml @@ -55,6 +55,9 @@ jobs: ccache -s ccache -z + - name: install dependencies + run: pip3 install dataclasses + - name: check environment run: | export diff --git a/.github/workflows/mavros_offboard_tests.yml b/.github/workflows/mavros_offboard_tests.yml index 0979c5a175b1..60e87553923b 100644 --- a/.github/workflows/mavros_offboard_tests.yml +++ b/.github/workflows/mavros_offboard_tests.yml @@ -50,6 +50,9 @@ jobs: ccache -s ccache -z + - name: install dependencies + run: pip3 install dataclasses + - name: check environment run: | export diff --git a/Makefile b/Makefile index 32a6e17c0dab..c97b7ae281dc 100644 --- a/Makefile +++ b/Makefile @@ -490,7 +490,7 @@ shellcheck_all: validate_module_configs: @find "$(SRC_DIR)"/src/modules "$(SRC_DIR)"/src/drivers "$(SRC_DIR)"/src/lib -name *.yaml -type f \ -not -path "$(SRC_DIR)/src/lib/mixer_module/*" -not -path "$(SRC_DIR)/src/lib/crypto/libtommath/*" -print0 | \ - xargs -0 "$(SRC_DIR)"/Tools/validate_yaml.py --schema-file "$(SRC_DIR)"/validation/module_schema.yaml + xargs -0 "$(SRC_DIR)"/Tools/validate.py --schema-file "$(SRC_DIR)"/validation/module_schema.yaml # Cleanup # -------------------------------------------------------------------- diff --git a/Tools/migrate_c_params.py b/Tools/migrate_c_params.py new file mode 100755 index 000000000000..a51e75c39ba3 --- /dev/null +++ b/Tools/migrate_c_params.py @@ -0,0 +1,497 @@ +#!/usr/bin/python3 + +""" +Migrate c parameter definitions to yaml module definitions. + +This script is used to transition legacy c parameter definitions to +yaml module definitions. It parses each specified legacy c file +and produces a corresponding yaml definition in the same directory. +For modules with multiple parameter c files and/or existing module.yaml files, +the resulting list of yaml files must be merged separately, either manually +or with a tool like yq4: + + yq eval-all '. as $item ireduce ({}; . *+ $item)' *.yaml + +The legacy files and temporary yaml files can then be manually deleted +and the CMakeLists.txt updated after proofreading. +""" + +import argparse +import ast +import sys +import re +import math +import logging +import os +from dataclasses import dataclass, field +from typing import Any + +import yaml + + +global default_var +default_var = {} + + +# define sorting order of the fields +PRIORITIES = { + "board": 9, + "short_desc": 8, + "long_desc": 7, + "min": 5, + "max": 4, + "unit": 3, + "decimal": 2, + # all others == 0 (sorted alphabetically) +} + + +@dataclass +class Parameter: + """ + Single parameter + """ + + name: str + type: str + fields: dict[str, str] = field(init=False, default_factory=dict) + default: str = "" + category: str = "" + enum: dict[str, str] = field(init=False, default_factory=dict) + bitmask: dict[int, str] = field(init=False, default_factory=dict) + volatile: bool = False + boolean: bool = False + + def __lt__(self, other): + return self.name < other.name + + @property + def field_keys(self) -> list[str]: + """ + Return list of existing field codes in convenient order + """ + keys = self.fields.keys() + keys = sorted(keys) + keys = sorted(keys, key=lambda x: PRIORITIES.get(x, 0), reverse=True) + return keys + + +@dataclass +class ParameterGroup: + """ + Single parameter group + """ + + name: str + parameters: list[Parameter] = field(init=False, default_factory=list) + no_code_generation: bool = False + + +class SourceParser: + """ + Parses provided data and stores all found parameters internally. + """ + + re_split_lines = re.compile(r'[\r\n]+') + re_comment_start = re.compile(r'^\/\*\*') + re_comment_content = re.compile(r'^\*\s*(.*)') + re_comment_tag = re.compile(r'@([a-zA-Z][a-zA-Z0-9_]*)\s*(.*)') + re_comment_end = re.compile(r'(.*?)\s*\*\/') + re_parameter_definition = re.compile(r'PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*,\s*([^ ,\)]+)\s*\)\s*;') + re_px4_parameter_definition = re.compile(r'PX4_PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*\)\s*;') + re_px4_param_default_definition = re.compile(r'#define\s*PARAM_([A-Z_][A-Z0-9_]*)\s*([^ ,\)]+)\s*') + re_cut_type_specifier = re.compile(r'[a-z]+$') + re_is_a_number = re.compile(r'^-?[0-9\.]') + re_remove_dots = re.compile(r'\.+$') + re_remove_carriage_return = re.compile('\n+') + + valid_tags = set(["group", "board", "min", "max", "unit", "decimal", + "increment", "reboot_required", "value", "boolean", + "bit", "category", "volatile"]) + + # Order of parameter groups + priority = { + # All other groups = 0 (sort alphabetically) + "Miscellaneous": -10 + } + + def __init__(self): + self.param_groups = {} + + def parse(self, contents): + """ + Incrementally parse program contents and append all found parameters + to the list. + """ + # This code is essentially a comment-parsing grammar. "state" + # represents parser state. It contains human-readable state + # names. + state = None + for line in self.re_split_lines.split(contents): + line = line.strip() + # Ignore empty lines + if line == "": + continue + if self.re_comment_start.match(line): + state = "wait-short" + short_desc = None + long_desc = None + tags = {} + def_values = {} + def_bitmask = {} + elif state is not None and state != "comment-processed": + m = self.re_comment_end.search(line) + if m: + line = m.group(1) + last_comment_line = True + else: + last_comment_line = False + m = self.re_comment_content.match(line) + if m: + comment_content = m.group(1) + if comment_content == "": + # When short comment ends with empty comment line, + # start waiting for the next part - long comment. + if state == "wait-short-end": + state = "wait-long" + else: + m = self.re_comment_tag.match(comment_content) + if m: + tag, desc = m.group(1, 2) + if (tag == "value"): + # Take the meta info string and split + # the code and description + metainfo = desc.split(" ", 1) + def_values[metainfo[0]] = metainfo[1] + elif (tag == "bit"): + # Take the meta info string and split + # the code and description + metainfo = desc.split(" ", 1) + def_bitmask[metainfo[0]] = metainfo[1] + else: + tags[tag] = desc + current_tag = tag + state = "wait-tag-end" + elif state == "wait-short": + # Store first line of the short description + short_desc = comment_content + state = "wait-short-end" + elif state == "wait-short-end": + # Append comment line to the short description + short_desc += "\n" + comment_content + elif state == "wait-long": + # Store first line of the long description + long_desc = comment_content + state = "wait-long-end" + elif state == "wait-long-end": + # Append comment line to the long description + long_desc += "\n" + comment_content + elif state == "wait-tag-end": + # Append comment line to the tag text + tags[current_tag] += "\n" + comment_content + else: + raise AssertionError( + "Invalid parser state: %s" % state) + elif not last_comment_line: + # Invalid comment line (inside comment, but not + # startin with "*" or "*/". Reset parsed content. + state = None + if last_comment_line: + state = "comment-processed" + else: + tp = None + name = None + defval = "" + # Non-empty line outside the comment + m = self.re_px4_param_default_definition.match(line) + # Default value handling + if m: + name_m, defval_m = m.group(1, 2) + default_var[name_m] = defval_m + m = self.re_parameter_definition.match(line) + if m: + tp, name, defval = m.group(1, 2, 3) + else: + m = self.re_px4_parameter_definition.match(line) + if m: + tp, name = m.group(1, 2) + if (name+'_DEFAULT') in default_var: + defval = default_var[name+'_DEFAULT'] + if tp is not None: + # Remove trailing type specifier from numbers: 0.1f => 0.1 + if defval != "" and self.re_is_a_number.match(defval): + defval = self.re_cut_type_specifier.sub('', defval) + param = Parameter(name=name, type=tp, default=defval) + param.fields["short_desc"] = name + # If comment was found before the parameter declaration, + # inject its data into the newly created parameter. + group = "Miscellaneous" + if state == "comment-processed": + if short_desc is not None: + if '\n' in short_desc: + raise Exception('short description must be a single line (parameter: {:})'.format(name)) + if len(short_desc) > 150: + raise Exception('short description too long (150 max, is {:}, parameter: {:})'.format(len(short_desc), name)) + param.fields["short_desc"] = self.re_remove_dots.sub('', short_desc) + if long_desc is not None: + long_desc = self.re_remove_carriage_return.sub(' ', long_desc) + param.fields["long_desc"] = long_desc + for tag in tags: + if tag == "group": + group = tags[tag] + elif tag == "volatile": + param.volatile = True + elif tag == "category": + param.category = tags[tag] + elif tag == "boolean": + param.boolean = True + elif tag not in self.valid_tags: + sys.stderr.write("Skipping invalid documentation tag: '%s'\n" % tag) + return False + else: + param.fields[tag] = tags[tag] + for def_value in def_values: + param.enum[def_value] = def_values[def_value] + for def_bit in def_bitmask: + param.bitmask[def_bit] = def_bitmask[def_bit] + # Store the parameter + if group not in self.param_groups: + self.param_groups[group] = ParameterGroup(group) + self.param_groups[group].parameters.append(param) + state = None + return True + + def validate(self): + """ + Validates the parameter meta data. + """ + seenParamNames = [] + #allowedUnits should match set defined in /Firmware/validation/module_schema.yaml + allowedUnits = set ([ + '%', 'Hz', '1/s', 'mAh', + 'rad', '%/rad', 'rad/s', 'rad/s^2', '%/rad/s', 'rad s^2/m', 'rad s/m', + 'bit/s', 'B/s', + 'deg', 'deg*1e7', 'deg/s', + 'celcius', 'gauss', 'gauss/s', 'gauss^2', + 'hPa', 'kg', 'kg/m^2', 'kg m^2', + 'mm', 'm', 'm/s', 'm^2', 'm/s^2', 'm/s^3', 'm/s^2/sqrt(Hz)', 'm/s/rad', + 'Ohm', 'V', 'A', + 'us', 'ms', 's', + 'S', 'A/%', '(m/s^2)^2', 'm/m', 'tan(rad)^2', '(m/s)^2', 'm/rad', + 'm/s^3/sqrt(Hz)', 'm/s/sqrt(Hz)', 's/(1000*PWM)', '%m/s', 'min', 'us/C', '1/s/sqrt(Hz)', + 'N/(m/s)', 'Nm/rad', 'Nm/(rad/s)', 'Nm', 'N', + 'normalized_thrust/s', 'normalized_thrust', 'norm', 'SD','', 'RPM']) + + for group in self.parameter_groups: + for param in sorted(group.parameters): + name = param.name + if len(name) > 16: + sys.stderr.write("Parameter Name {0} is too long (Limit is 16)\n".format(name)) + return False + board = param.fields.get("board", "") + # Check for duplicates + name_plus_board = name + "+" + board + for seenParamName in seenParamNames: + if seenParamName == name_plus_board: + sys.stderr.write("Duplicate parameter definition: {0}\n".format(name_plus_board)) + return False + seenParamNames.append(name_plus_board) + # Validate values + default = param.default + min = param.fields.get("min", "") + max = param.fields.get("max", "") + units = param.fields.get("unit", "") + if units not in allowedUnits: + sys.stderr.write("Invalid unit in {0}: {1}\n".format(name, units)) + return False + #sys.stderr.write("{0} default:{1} min:{2} max:{3}\n".format(name, default, min, max)) + if default != "" and not self.is_number(default): + sys.stderr.write("Default value not number: {0} {1}\n".format(name, default)) + return False + # if default != "" and "." not in default: + # sys.stderr.write("Default value does not contain dot (e.g. 10 needs to be written as 10.0): {0} {1}\n".format(name, default)) + # return False + if min != "": + if not self.is_number(default): + sys.stderr.write("Min value not number: {0} {1}\n".format(name, min)) + return False + if default != "" and float(default) < float(min): + sys.stderr.write("Default value is smaller than min: {0} default:{1} min:{2}\n".format(name, default, min)) + return False + if max != "": + if not self.is_number(max): + sys.stderr.write("Max value not number: {0} {1}\n".format(name, max)) + return False + if default != "" and float(default) > float(max): + sys.stderr.write("Default value is larger than max: {0} default:{1} max:{2}\n".format(name, default, max)) + return False + for code in sorted(param.enum, key=float): + if not self.is_number(code): + sys.stderr.write("Min value not number: {0} {1}\n".format(name, code)) + return False + if param.enum.get(code, "") == "": + sys.stderr.write("Description for enum value is empty: {0} {1}\n".format(name, code)) + return False + for index in sorted(param.bitmask.keys(), key=float): + if not self.is_number(index): + sys.stderr.write("bit value not number: {0} {1}\n".format(name, index)) + return False + if not int(min) <= math.pow(2, int(index)) <= int(max): + sys.stderr.write("Bitmask bit must be between {0} and {1}: {2} {3}\n".format(min, max, name, math.pow(2, int(index)))) + return False + if param.bitmask.get(index, "") == "": + sys.stderr.write("Description for bitmask bit is empty: {0} {1}\n".format(name, index)) + return False + return True + + def is_number(self, num): + try: + float(num) + return True + except ValueError: + return False + + @property + def parameter_groups(self) -> list[ParameterGroup]: + """ + Returns the parsed list of parameters. Every parameter is a Parameter + object. Note that returned object is not a copy. Modifications affect + state of the parser. + """ + groups = self.param_groups.values() + groups = sorted(groups, key=lambda x: x.name) + groups = sorted(groups, key=lambda x: self.priority.get(x.name, 0), + reverse=True) + + return groups + + +def parse(filename: str) -> list[ParameterGroup]: + with open(filename) as f: + cdata = f.read() + + parser = SourceParser() + if not parser.parse(cdata): + logging.error(f"Error parsing c parameter file {filename}") + sys.exit(1) + if not parser.validate(): + logging.error(f"Error while validating c parameter file {filename}") + sys.exit(1) + + return parser.parameter_groups + + +def cast(val: str) -> Any: + if val == "true": + return True + elif val == "false": + return False + try: + return ast.literal_eval(val) + except ValueError: + return val + + +def generate_yaml(filename: str, groups: list[ParameterGroup]) -> str: + data = dict() + + module_name = os.path.dirname(os.path.realpath(filename)).split(os.sep)[-1] + + data["module_name"] = module_name + data["parameters"] = list() + + for group in groups: + g = dict() + g["group"] = group.name + g["definitions"] = dict() + + for parameter in group.parameters: + p = dict() + + p["default"] = cast(parameter.default) + if parameter.category != "": + p["category"] = parameter.category.title() + p["volatile"] = bool(parameter.volatile) + # the enum check has to happen first + # since some parameters are both boolean and enum at the same time + # (even with more than 0 and 1 as options for some reason) so let's assume + # they are enums not booleans + if len(parameter.enum) > 0: + p["type"] = "enum" + p["values"] = dict() + for key, val in parameter.enum.items(): + try: + p["values"][int(key)] = val + except ValueError: + p["values"][float(key)] = val + p["type"] = "float" + elif parameter.boolean: + p["type"] = "boolean" + elif len(parameter.bitmask) > 0: + p["type"] = "bitmask" + p["bit"] = dict() + for key, val in parameter.bitmask.items(): + p["bit"][int(key)] = val.strip() + elif parameter.type == "FLOAT": + p["type"] = "float" + else: + p["type"] = "int32" + + p["description"] = dict() + p["description"]["short"] = parameter.fields["short_desc"] + del parameter.fields["short_desc"] + if "long_desc" in parameter.fields: + p["description"]["long"] = parameter.fields["long_desc"] + del parameter.fields["long_desc"] + + for key, val in parameter.fields.items(): + try: + p[key] = cast(val) + except SyntaxError: + p[key] = val + + g["definitions"][parameter.name] = p + + data["parameters"].append(g) + + return yaml.dump(data) + + +def main(): + parser = argparse.ArgumentParser(description="Migrate legacy c parameter definitions to yaml") + parser.add_argument('input_file', nargs='+', help='input file(s)') + parser.add_argument('--update-cmake', action=argparse.BooleanOptionalAction) + args = parser.parse_args() + + input_files = args.input_file + update_cmake = args.update_cmake + + logging.basicConfig(level=logging.INFO) + + for filename in input_files: + logging.info(f"Migrating c parameter file {filename}") + + parameter_groups = parse(filename) + output = generate_yaml(filename, parameter_groups) + + dirname, fname = os.path.split(os.path.realpath(filename)) + fname = fname.split(".")[0] + with open(os.path.join(dirname, f"module.{fname}.yaml"), "w") as f: + f.write(output) + if update_cmake: + with open(os.path.join(dirname, "CMakeLists.txt"), "r+") as f: + content = f.read() + if "MODULE_CONFIG" not in content: + try: + index = content.index("DEPENDS") + except ValueError: + index = content.index("px4_add_module") + index += content[index:].index(")") + content = content[:index] + "MODULE_CONFIG\n\t\tmodule.yaml\n\t" + content[index:] + f.seek(0) + f.write(content) + f.truncate() + + +if __name__ == "__main__": + main() diff --git a/Tools/module_config/generate_params.py b/Tools/module_config/generate_params.py index 68a9689ac3d9..6fa70a75e9a4 100755 --- a/Tools/module_config/generate_params.py +++ b/Tools/module_config/generate_params.py @@ -130,6 +130,8 @@ def parse_yaml_parameters_config(yaml_config, ethernet_supported): for tag in ['decimal', 'increment', 'category', 'volatile', 'min', 'max', 'unit', 'reboot_required']: if tag in param: + if type(param[tag]) is bool and not param[tag]: + continue tags += '\n * @{:} {:}'.format(tag, param[tag]) for i in range(num_instances): diff --git a/Tools/serial/generate_config.py b/Tools/serial/generate_config.py index 84a9c342aad4..065c3a2f2d16 100755 --- a/Tools/serial/generate_config.py +++ b/Tools/serial/generate_config.py @@ -269,7 +269,7 @@ def parse_yaml_serial_config(yaml_config): else: default_port_str = port_config['default'] - if default_port_str != "": + if default_port_str != "" and default_port_str != 0: if default_port_str not in serial_ports: raise Exception("Default Port {:} not found for {:}".format(default_port_str, serial_command['label'])) diff --git a/Tools/validate.py b/Tools/validate.py new file mode 100755 index 000000000000..8e88a36ed80e --- /dev/null +++ b/Tools/validate.py @@ -0,0 +1,88 @@ +#! /usr/bin/env python3 +""" Script to validate YAML file(s) against a YAML schema file """ + +import argparse +import logging +import pprint +import sys +import os + +try: + import yaml +except ImportError as e: + print("Failed to import yaml: " + str(e)) + print("") + print("You may need to install it using:") + print(" pip3 install --user pyyaml") + print("") + sys.exit(1) + +try: + import cerberus +except ImportError as e: + print("Failed to import cerberus: " + str(e)) + print("") + print("You may need to install it using:") + print(" pip3 install --user cerberus") + print("") + sys.exit(1) + + +def load_data_file(file_name: str): + with open(file_name) as stream: + try: + return yaml.safe_load(stream) + except: + raise Exception("Unable to parse schema file: syntax error or unsupported file format") + + +def main(): + parser = argparse.ArgumentParser(description='Validate YAML or JSON file(s) against a schema') + + parser.add_argument('data_file', nargs='+', help='data file(s)') + parser.add_argument('--schema-file', type=str, action='store', + help='schema file', required=True) + parser.add_argument('--skip-if-no-schema', dest='skip_if_no_schema', + action='store_true', + help='Skip test if schema file does not exist') + parser.add_argument('-v', '--verbose', dest='verbose', action='store_true', + help='Verbose Output') + + args = parser.parse_args() + + data_files = args.data_file + schema_file = args.schema_file + + if args.verbose: + logging.basicConfig(level=logging.INFO) + else: + logging.basicConfig(level=logging.ERROR) + + if args.skip_if_no_schema and not os.path.isfile(schema_file): + logging.info(f"Schema file {schema_file} not found, skipping") + sys.exit(0) + + # load the schema + schema = load_data_file(schema_file) + validator = cerberus.Validator(schema, allow_unknown=False) + + # validate the specified data files + for data_file in data_files: + logging.info(f"Validating {data_file}") + + document = load_data_file(data_file) + + # ignore top-level entries prefixed with __ for yaml module definitions + for key in list(document.keys()): + if key.startswith('__'): + del document[key] + + if not validator.validate(document): + logging.error(f"Found validation errors with {data_file}:") + logging.error(pprint.pformat(validator.errors)) + + raise Exception("Validation of {:} failed".format(data_file)) + + +if __name__ == "__main__": + main() diff --git a/Tools/validate_json.py b/Tools/validate_json.py index b80dad3198be..91e744006208 100755 --- a/Tools/validate_json.py +++ b/Tools/validate_json.py @@ -47,7 +47,9 @@ try: validate(instance=json_data, schema=schema) - except: + except Exception as ex: + print(ex.path.pop(), ex.instance) print("JSON validation for {:} failed (schema: {:})".format(json_file, schema_file)) raise + diff --git a/Tools/validate_yaml.py b/Tools/validate_yaml.py deleted file mode 100755 index 3a2d022bfc88..000000000000 --- a/Tools/validate_yaml.py +++ /dev/null @@ -1,68 +0,0 @@ -#! /usr/bin/env python3 -""" Script to validate YAML file(s) against a YAML schema file """ - -from __future__ import print_function - -import argparse -import sys - -try: - import yaml -except ImportError as e: - print("Failed to import yaml: " + str(e)) - print("") - print("You may need to install it using:") - print(" pip3 install --user pyyaml") - print("") - sys.exit(1) - -try: - import cerberus -except ImportError as e: - print("Failed to import cerberus: " + str(e)) - print("") - print("You may need to install it using:") - print(" pip3 install --user cerberus") - print("") - sys.exit(1) - - -parser = argparse.ArgumentParser(description='Validate YAML file(s) against a schema') - -parser.add_argument('yaml_file', nargs='+', help='YAML config file(s)') -parser.add_argument('--schema-file', type=str, action='store', - help='YAML schema file', required=True) -parser.add_argument('-v', '--verbose', dest='verbose', action='store_true', - help='Verbose Output') - -args = parser.parse_args() -schema_file = args.schema_file -yaml_files = args.yaml_file -verbose = args.verbose - -def load_yaml_file(file_name): - with open(file_name, 'r') as stream: - try: - return yaml.safe_load(stream) - except yaml.YAMLError as exc: - print(exc) - raise - -# load the schema -schema = load_yaml_file(schema_file) -validator = cerberus.Validator(schema) - -# validate yaml files -for yaml_file in yaml_files: - if verbose: print("Validating {:}".format(yaml_file)) - document = load_yaml_file(yaml_file) - # ignore top-level entries prefixed with __ - for key in list(document.keys()): - if key.startswith('__'): del document[key] - - if not validator.validate(document): - print("Validation Errors:") - print(validator.errors) - print("") - raise Exception("Validation of {:} failed".format(yaml_file)) - diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 000000000000..9980a1f3e1a3 --- /dev/null +++ b/requirements.txt @@ -0,0 +1,24 @@ +argparse +argcomplete +coverage +cerberus +empy +jinja2 +kconfiglib +matplotlib==3.0.* +numpy +nunavut>=1.1.0 +packaging +pkgconfig +pyros-genmsg +pyulog +pyyaml +requests +serial +six +toml +psutil +wheel +jsonschema +dataclasses +pynacl diff --git a/src/drivers/actuators/modalai_esc/CMakeLists.txt b/src/drivers/actuators/modalai_esc/CMakeLists.txt index 2e1bc60a2727..2e4a6fcf0e91 100644 --- a/src/drivers/actuators/modalai_esc/CMakeLists.txt +++ b/src/drivers/actuators/modalai_esc/CMakeLists.txt @@ -45,6 +45,8 @@ px4_add_module( qc_esc_packet_types.h qc_esc_packet.c qc_esc_packet.h + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/actuators/modalai_esc/module.yaml b/src/drivers/actuators/modalai_esc/module.yaml new file mode 100644 index 000000000000..3f12804150f4 --- /dev/null +++ b/src/drivers/actuators/modalai_esc/module.yaml @@ -0,0 +1,113 @@ +module_name: modalai_esc +parameters: + - definitions: + UART_ESC_BAUD: + default: 250000 + description: + long: Default rate is 250Kbps, which is used in off-the-shelf MoadalAI ESC products. + short: UART ESC baud rate + type: int32 + unit: bit/s + volatile: false + UART_ESC_CONFIG: + default: 0 + description: + long: Selects what type of UART ESC, if any, is being used. + short: UART ESC configuration + max: 1 + min: 0 + reboot_required: true + type: enum + values: + 0: '- Disabled' + 1: '- VOXL ESC' + volatile: false + UART_ESC_MODE: + default: 0 + description: + long: Selects what type of mode is enabled, if any + short: UART ESC Mode + max: 2 + min: 0 + reboot_required: true + type: enum + values: + 0: '- None' + 1: '- Turtle Mode enabled via AUX1' + 2: '- Turtle Mode enabled via AUX2' + volatile: false + UART_ESC_MOTOR1: + default: 3 + description: + short: UART ESC Motor 1 Mapping. 1-4 (negative for reversal) + max: 4 + min: -4 + type: int32 + volatile: false + UART_ESC_MOTOR2: + default: 2 + description: + short: UART ESC Motor 2 Mapping. 1-4 (negative for reversal) + max: 4 + min: -4 + type: int32 + volatile: false + UART_ESC_MOTOR3: + default: 4 + description: + short: UART ESC Motor 3 Mapping. 1-4 (negative for reversal) + max: 4 + min: -4 + type: int32 + volatile: false + UART_ESC_MOTOR4: + default: 1 + description: + short: UART ESC Motor 4 Mapping. 1-4 (negative for reversal) + max: 4 + min: -4 + type: int32 + volatile: false + UART_ESC_RPM_MAX: + default: 15000 + description: + long: Maximum RPM for ESC + short: UART ESC RPM Max + type: int32 + unit: RPM + volatile: false + UART_ESC_RPM_MIN: + default: 5500 + description: + long: Minimum RPM for ESC + short: UART ESC RPM Min + type: int32 + unit: RPM + volatile: false + group: UART ESC + - definitions: + UART_ESC_DEAD1: + decimal: 10 + default: 0.3 + description: + long: Must be greater than Deadzone 2. Absolute value of stick position needed to activate a motor. + short: UART ESC Mode Deadzone 1 + increment: 0.01 + max: 0.99 + min: 0.01 + type: float + volatile: false + group: UART ESC Mode Deadzone 1 + - definitions: + UART_ESC_DEAD2: + decimal: 10 + default: 0.02 + description: + long: Must be less than Deadzone 1. Absolute value of stick position considered no longer on the X or Y axis, thus targetting a specific motor (single). + short: UART ESC Mode Deadzone 2 + increment: 0.01 + max: 0.99 + min: 0.01 + type: float + volatile: false + group: UART ESC Mode Deadzone 2 diff --git a/src/drivers/actuators/modalai_esc/parameters.c b/src/drivers/actuators/modalai_esc/parameters.c deleted file mode 100644 index 3c7c21a66e28..000000000000 --- a/src/drivers/actuators/modalai_esc/parameters.c +++ /dev/null @@ -1,167 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * UART ESC configuration - * - * Selects what type of UART ESC, if any, is being used. - * - * @reboot_required true - * - * @group UART ESC - * @value 0 - Disabled - * @value 1 - VOXL ESC - * @min 0 - * @max 1 - */ -PARAM_DEFINE_INT32(UART_ESC_CONFIG, 0); - -/** - * UART ESC baud rate - * - * Default rate is 250Kbps, which is used in off-the-shelf MoadalAI ESC products. - * - * @group UART ESC - * @unit bit/s - */ -PARAM_DEFINE_INT32(UART_ESC_BAUD, 250000); - -/** - * Motor mappings for ModalAI ESC M004 - * - * HW Channel Idexes (PX4 Indexes) (note: silkscreen shows 0 indexed) - * 4(1) 3(4) - * [front] - * 1(3) 2(2) - */ - -/** - * UART ESC Motor 1 Mapping. 1-4 (negative for reversal). - * - * @group UART ESC - * @min -4 - * @max 4 - */ -PARAM_DEFINE_INT32(UART_ESC_MOTOR1, 3); - -/** - *UART ESC Motor 2 Mapping. 1-4 (negative for reversal). - * - * @group UART ESC - * @min -4 - * @max 4 - */ -PARAM_DEFINE_INT32(UART_ESC_MOTOR2, 2); - -/** - * UART ESC Motor 3 Mapping. 1-4 (negative for reversal). - * - * @group UART ESC - * @min -4 - * @max 4 - */ -PARAM_DEFINE_INT32(UART_ESC_MOTOR3, 4); - -/** - * UART ESC Motor 4 Mapping. 1-4 (negative for reversal). - * - * @group UART ESC - * @min -4 - * @max 4 - */ -PARAM_DEFINE_INT32(UART_ESC_MOTOR4, 1); - -/** - * UART ESC RPM Min - * - * Minimum RPM for ESC - * - * @group UART ESC - * @unit RPM - */ -PARAM_DEFINE_INT32(UART_ESC_RPM_MIN, 5500); - -/** - * UART ESC RPM Max - * - * Maximum RPM for ESC - * - * @group UART ESC - * @unit RPM - */ -PARAM_DEFINE_INT32(UART_ESC_RPM_MAX, 15000); - -/** - * UART ESC Mode - * - * Selects what type of mode is enabled, if any - * - * @reboot_required true - * - * @group UART ESC - * @value 0 - None - * @value 1 - Turtle Mode enabled via AUX1 - * @value 2 - Turtle Mode enabled via AUX2 - * @min 0 - * @max 2 - */ -PARAM_DEFINE_INT32(UART_ESC_MODE, 0); - -/** - * UART ESC Mode Deadzone 1. - * - * Must be greater than Deadzone 2. - * Absolute value of stick position needed to activate a motor. - * - * @group UART ESC Mode Deadzone 1 - * @min 0.01 - * @max 0.99 - * @decimal 10 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(UART_ESC_DEAD1, 0.30f); - -/** - * UART ESC Mode Deadzone 2. - * - * Must be less than Deadzone 1. - * Absolute value of stick position considered no longer on the X or Y axis, - * thus targetting a specific motor (single). - * - * @group UART ESC Mode Deadzone 2 - * @min 0.01 - * @max 0.99 - * @decimal 10 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(UART_ESC_DEAD2, 0.02f); diff --git a/src/drivers/adc/ads1115/CMakeLists.txt b/src/drivers/adc/ads1115/CMakeLists.txt index d65265709d61..f4d6c5ff96e9 100644 --- a/src/drivers/adc/ads1115/CMakeLists.txt +++ b/src/drivers/adc/ads1115/CMakeLists.txt @@ -37,5 +37,7 @@ px4_add_module( SRCS ads1115_main.cpp ADS1115.cpp + MODULE_CONFIG + module.yaml DEPENDS ) \ No newline at end of file diff --git a/src/drivers/adc/ads1115/ads1115_params.c b/src/drivers/adc/ads1115/ads1115_params.c deleted file mode 100644 index 560637db00a7..000000000000 --- a/src/drivers/adc/ads1115/ads1115_params.c +++ /dev/null @@ -1,44 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Enable external ADS1115 ADC - * - * If enabled, the internal ADC is not used. - * - * @boolean - * @reboot_required true - * @group Sensors - */ -PARAM_DEFINE_INT32(ADC_ADS1115_EN, 0); - diff --git a/src/drivers/adc/ads1115/module.yaml b/src/drivers/adc/ads1115/module.yaml new file mode 100644 index 000000000000..bcd626816f2b --- /dev/null +++ b/src/drivers/adc/ads1115/module.yaml @@ -0,0 +1,12 @@ +module_name: ads1115 +parameters: + - definitions: + ADC_ADS1115_EN: + default: 0 + description: + long: If enabled, the internal ADC is not used. + short: Enable external ADS1115 ADC + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/barometer/goertek/spl06/CMakeLists.txt b/src/drivers/barometer/goertek/spl06/CMakeLists.txt index 044ca466a52d..fe2de6f72eb4 100644 --- a/src/drivers/barometer/goertek/spl06/CMakeLists.txt +++ b/src/drivers/barometer/goertek/spl06/CMakeLists.txt @@ -40,6 +40,8 @@ px4_add_module( SPL06_I2C.cpp SPL06_SPI.cpp spl06_main.cpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/barometer/goertek/spl06/module.yaml b/src/drivers/barometer/goertek/spl06/module.yaml new file mode 100644 index 000000000000..f319608a4583 --- /dev/null +++ b/src/drivers/barometer/goertek/spl06/module.yaml @@ -0,0 +1,11 @@ +module_name: spl06 +parameters: + - definitions: + SENS_EN_SPL06: + default: 0 + description: + short: Goertek SPL06 Barometer (external I2C) + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/barometer/goertek/spl06/parameters.c b/src/drivers/barometer/goertek/spl06/parameters.c deleted file mode 100644 index 2712844477a2..000000000000 --- a/src/drivers/barometer/goertek/spl06/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Goertek SPL06 Barometer (external I2C) - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_SPL06, 0); diff --git a/src/drivers/batt_smbus/CMakeLists.txt b/src/drivers/batt_smbus/CMakeLists.txt index bf60e80af307..f17bcc7d3dbf 100644 --- a/src/drivers/batt_smbus/CMakeLists.txt +++ b/src/drivers/batt_smbus/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( SRCS batt_smbus.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers__smbus ) diff --git a/src/drivers/batt_smbus/module.yaml b/src/drivers/batt_smbus/module.yaml new file mode 100644 index 000000000000..938104b60635 --- /dev/null +++ b/src/drivers/batt_smbus/module.yaml @@ -0,0 +1,32 @@ +module_name: batt_smbus +parameters: + - definitions: + BAT1_C_MULT: + decimal: 1 + default: 1.0 + description: + short: Capacity/current multiplier for high-current capable SMBUS battery + reboot_required: true + type: float + volatile: false + BAT1_SMBUS_MODEL: + default: 0 + description: + short: Battery device model + max: 2 + min: 0 + reboot_required: true + type: enum + values: + 0: AutoDetect + 1: BQ40Z50 based + 2: BQ40Z80 based + volatile: false + SENS_EN_BATT: + default: 0 + description: + short: SMBUS Smart battery driver BQ40Z50 and BQ40Z80 + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/batt_smbus/parameters.c b/src/drivers/batt_smbus/parameters.c deleted file mode 100644 index 0d256c757724..000000000000 --- a/src/drivers/batt_smbus/parameters.c +++ /dev/null @@ -1,64 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * SMBUS Smart battery driver BQ40Z50 and BQ40Z80 - * - * @reboot_required true - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_BATT, 0); - -/** - * Capacity/current multiplier for high-current capable SMBUS battery - * - * @reboot_required true - * @decimal 1 - * @group Sensors - */ -PARAM_DEFINE_FLOAT(BAT1_C_MULT, 1.0f); - -/** - * Battery device model - * - * @reboot_required true - * @min 0 - * @max 2 - * @group Sensors - * @value 0 AutoDetect - * @value 1 BQ40Z50 based - * @value 2 BQ40Z80 based - */ -PARAM_DEFINE_INT32(BAT1_SMBUS_MODEL, 0); diff --git a/src/drivers/camera_capture/CMakeLists.txt b/src/drivers/camera_capture/CMakeLists.txt index 37e9e88b86eb..df0ac8606fc1 100644 --- a/src/drivers/camera_capture/CMakeLists.txt +++ b/src/drivers/camera_capture/CMakeLists.txt @@ -44,6 +44,8 @@ px4_add_module( -DPARAM_PREFIX="${PARAM_PREFIX}" SRCS camera_capture.cpp + MODULE_CONFIG + module.yaml DEPENDS arch_io_pins ) diff --git a/src/drivers/camera_capture/camera_capture_params.c b/src/drivers/camera_capture/camera_capture_params.c deleted file mode 100644 index f82d0318bf3d..000000000000 --- a/src/drivers/camera_capture/camera_capture_params.c +++ /dev/null @@ -1,87 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file camera_capture_params.c - * Camera capture parameters - * - * @author Mohammed Kabir - */ -/** - * Camera strobe delay - * - * This parameter sets the delay between image integration start and strobe firing - * - * @unit ms - * @min 0.0 - * @max 100.0 - * @decimal 1 - * @group Camera Capture - */ -PARAM_DEFINE_FLOAT(CAM_CAP_DELAY, 0.0f); - -/** - * Camera capture feedback - * - * Enables camera capture feedback - * - * @boolean - * @group Camera Control - * @reboot_required true - */ -PARAM_DEFINE_INT32(CAM_CAP_FBACK, 0); - -/** - * Camera capture timestamping mode - * - * Change time measurement - * - * @value 0 Get absolute timestamp - * @value 1 Get timestamp of mid exposure (active high) - * @value 2 Get timestamp of mid exposure (active low) - * - * @group Camera Control - * @reboot_required true - */ -PARAM_DEFINE_INT32(CAM_CAP_MODE, 0); - -/** - * Camera capture edge - * - * @value 0 Falling edge - * @value 1 Rising edge - * - * @group Camera Control - * @reboot_required true - */ -PARAM_DEFINE_INT32(CAM_CAP_EDGE, 0); \ No newline at end of file diff --git a/src/drivers/camera_capture/module.yaml b/src/drivers/camera_capture/module.yaml new file mode 100644 index 000000000000..c4d52b0d8655 --- /dev/null +++ b/src/drivers/camera_capture/module.yaml @@ -0,0 +1,47 @@ +module_name: camera_capture +parameters: + - definitions: + CAM_CAP_DELAY: + decimal: 1 + default: 0.0 + description: + long: This parameter sets the delay between image integration start and strobe firing + short: Camera strobe delay + max: 100.0 + min: 0.0 + type: float + unit: ms + volatile: false + group: Camera Capture + - definitions: + CAM_CAP_EDGE: + default: 0 + description: + short: Camera capture edge + reboot_required: true + type: enum + values: + 0: Falling edge + 1: Rising edge + volatile: false + CAM_CAP_FBACK: + default: 0 + description: + long: Enables camera capture feedback + short: Camera capture feedback + reboot_required: true + type: boolean + volatile: false + CAM_CAP_MODE: + default: 0 + description: + long: Change time measurement + short: Camera capture timestamping mode + reboot_required: true + type: enum + values: + 0: Get absolute timestamp + 1: Get timestamp of mid exposure (active high) + 2: Get timestamp of mid exposure (active low) + volatile: false + group: Camera Control diff --git a/src/drivers/camera_trigger/CMakeLists.txt b/src/drivers/camera_trigger/CMakeLists.txt index 77604edfc0db..e98804bc17b9 100644 --- a/src/drivers/camera_trigger/CMakeLists.txt +++ b/src/drivers/camera_trigger/CMakeLists.txt @@ -48,6 +48,8 @@ px4_add_module( interfaces/src/pwm.cpp interfaces/src/seagull_map2.cpp interfaces/src/gpio.cpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/camera_trigger/camera_trigger_params.c b/src/drivers/camera_trigger/camera_trigger_params.c deleted file mode 100644 index e51bacf7baa7..000000000000 --- a/src/drivers/camera_trigger/camera_trigger_params.c +++ /dev/null @@ -1,204 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015-2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file camera_trigger_params.c - * Camera trigger parameters - * - * @author Mohammed Kabir - * @author Andreas Bircher - * @author Lorenz Meier - */ - -/** -* Camera trigger Interface -* -* Selects the trigger interface -* -* @value 1 GPIO -* @value 2 Seagull MAP2 (over PWM) -* @value 3 MAVLink (forward via MAV_CMD_IMAGE_START_CAPTURE) -* @value 4 Generic PWM (IR trigger, servo) -* -* @reboot_required true -* @group Camera trigger -*/ -PARAM_DEFINE_INT32(TRIG_INTERFACE, 4); - -/** - * Camera trigger interval - * - * This parameter sets the time between two consecutive trigger events - * - * @unit ms - * @min 4.0 - * @max 10000.0 - * @decimal 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_INTERVAL, 40.0f); - -/** - * Minimum camera trigger interval - * - * This parameter sets the minimum time between two consecutive trigger events - * the specific camera setup is supporting. - * - * @unit ms - * @min 1.0 - * @max 10000.0 - * @decimal 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_MIN_INTERVA, 1.0f); - -/** - * Camera trigger polarity - * - * This parameter sets the polarity of the trigger (0 = active low, 1 = active high ) - * - * @value 0 Active low - * @value 1 Active high - * @min 0 - * @max 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_INT32(TRIG_POLARITY, 0); - -/** - * Camera trigger activation time - * - * This parameter sets the time the trigger needs to pulled high or low. - * - * @unit ms - * @min 0.1 - * @max 3000 - * @decimal 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 40.0f); - -/** - * Camera trigger mode - * - * @value 0 Disable - * @value 1 Time based, on command - * @value 2 Time based, always on - * @value 3 Distance based, always on - * @value 4 Distance based, on command (Survey mode) - * @min 0 - * @max 4 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_INT32(TRIG_MODE, 0); - -/** - * Camera trigger pin - * - * Selects which FMU pin is used (range: AUX1-AUX8 on Pixhawk controllers with an I/O board, - * MAIN1-MAIN8 on controllers without an I/O board). - * - * The PWM interface takes two pins per camera, while relay - * triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6. - * For GPIO mode Pin 6 will be triggered followed by 5. With a value of 65 pin 5 will - * be triggered followed by 6. Pins may be non contiguous. I.E. 16 or 61. - * In GPIO mode the delay pin to pin is < .2 uS. - * - * @min 1 - * @max 12345678 - * @decimal 0 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_INT32(TRIG_PINS, 56); - -/** - * Camera trigger pin extended - * - * This Bit mask selects which FMU pin is used (range: AUX9-AUX32) - * If the value is not 0 it takes precedence over TRIG_PINS. - * - * If bits above 8 are set that value is used as the selector for trigger pins. - * greater then 8. 0x00000300 Would be Pins 9,10. If the value is - * - * - * @min 0 - * @max 2147483647 - * @decimal 0 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_INT32(TRIG_PINS_EX, 0); - -/** - * Camera trigger distance - * - * Sets the distance at which to trigger the camera. - * - * @unit m - * @min 0 - * @increment 1 - * @decimal 1 - * @reboot_required true - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_DISTANCE, 25.0f); - -/** - * PWM output to trigger shot. - * - * @min 1000 - * @max 2000 - * @unit us - * @group Camera trigger - * @reboot_required true - */ -PARAM_DEFINE_INT32(TRIG_PWM_SHOOT, 1900); - - -/** - * PWM neutral output on trigger pin. - * - * @min 1000 - * @max 2000 - * @unit us - * @group Camera trigger - * @reboot_required true - */ -PARAM_DEFINE_INT32(TRIG_PWM_NEUTRAL, 1500); - diff --git a/src/drivers/camera_trigger/module.yaml b/src/drivers/camera_trigger/module.yaml new file mode 100644 index 000000000000..08c8c92d4e79 --- /dev/null +++ b/src/drivers/camera_trigger/module.yaml @@ -0,0 +1,135 @@ +module_name: camera_trigger +parameters: + - definitions: + TRIG_ACT_TIME: + decimal: 1 + default: 40.0 + description: + long: This parameter sets the time the trigger needs to pulled high or low. + short: Camera trigger activation time + max: 3000 + min: 0.1 + reboot_required: true + type: float + unit: ms + volatile: false + TRIG_DISTANCE: + decimal: 1 + default: 25.0 + description: + long: Sets the distance at which to trigger the camera. + short: Camera trigger distance + increment: 1 + min: 0 + reboot_required: true + type: float + unit: m + volatile: false + TRIG_INTERFACE: + default: 4 + description: + long: Selects the trigger interface + short: Camera trigger Interface + reboot_required: true + type: enum + values: + 1: GPIO + 2: Seagull MAP2 (over PWM) + 3: MAVLink (forward via MAV_CMD_IMAGE_START_CAPTURE) + 4: Generic PWM (IR trigger, servo) + volatile: false + TRIG_INTERVAL: + decimal: 1 + default: 40.0 + description: + long: This parameter sets the time between two consecutive trigger events + short: Camera trigger interval + max: 10000.0 + min: 4.0 + reboot_required: true + type: float + unit: ms + volatile: false + TRIG_MIN_INTERVA: + decimal: 1 + default: 1.0 + description: + long: This parameter sets the minimum time between two consecutive trigger events the specific camera setup is supporting. + short: Minimum camera trigger interval + max: 10000.0 + min: 1.0 + reboot_required: true + type: float + unit: ms + volatile: false + TRIG_MODE: + default: 0 + description: + short: Camera trigger mode + max: 4 + min: 0 + reboot_required: true + type: enum + values: + 0: Disable + 1: Time based, on command + 2: Time based, always on + 3: Distance based, always on + 4: Distance based, on command (Survey mode) + volatile: false + TRIG_PINS: + decimal: 0 + default: 56 + description: + long: 'Selects which FMU pin is used (range: AUX1-AUX8 on Pixhawk controllers with an I/O board, MAIN1-MAIN8 on controllers without an I/O board). The PWM interface takes two pins per camera, while relay triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6. For GPIO mode Pin 6 will be triggered followed by 5. With a value of 65 pin 5 will be triggered followed by 6. Pins may be non contiguous. I.E. 16 or 61. In GPIO mode the delay pin to pin is < .2 uS.' + short: Camera trigger pin + max: 12345678 + min: 1 + reboot_required: true + type: int32 + volatile: false + TRIG_PINS_EX: + decimal: 0 + default: 0 + description: + long: 'This Bit mask selects which FMU pin is used (range: AUX9-AUX32) If the value is not 0 it takes precedence over TRIG_PINS. If bits above 8 are set that value is used as the selector for trigger pins. greater then 8. 0x00000300 Would be Pins 9,10. If the value is' + short: Camera trigger pin extended + max: 2147483647 + min: 0 + reboot_required: true + type: int32 + volatile: false + TRIG_POLARITY: + default: 0 + description: + long: This parameter sets the polarity of the trigger (0 = active low, 1 = active high ) + short: Camera trigger polarity + max: 1 + min: 0 + reboot_required: true + type: enum + values: + 0: Active low + 1: Active high + volatile: false + TRIG_PWM_NEUTRAL: + default: 1500 + description: + short: PWM neutral output on trigger pin + max: 2000 + min: 1000 + reboot_required: true + type: int32 + unit: us + volatile: false + TRIG_PWM_SHOOT: + default: 1900 + description: + short: PWM output to trigger shot + max: 2000 + min: 1000 + reboot_required: true + type: int32 + unit: us + volatile: false + group: Camera trigger diff --git a/src/drivers/cyphal/module.yaml b/src/drivers/cyphal/module.yaml index 0b4f60e602dc..01c1417bde52 100644 --- a/src/drivers/cyphal/module.yaml +++ b/src/drivers/cyphal/module.yaml @@ -1,10 +1,145 @@ -module_name: UAVCANv1 +module_name: cyphal actuator_output: output_groups: - param_prefix: UCAN1_ESC channel_label: 'ESC' standard_params: - min: { min: 0, max: 8191, default: 1 } - max: { min: 0, max: 8191, default: 8191 } - failsafe: { min: 0, max: 8191 } + min: {min: 0, max: 8191, default: 1} + max: {min: 0, max: 8191, default: 8191} + failsafe: {min: 0, max: 8191} num_channels: 16 +parameters: + - definitions: + CYPHAL_BAUD: + default: 1000000 + description: + short: UAVCAN/CAN v1 bus bitrate + max: 1000000 + min: 20000 + reboot_required: true + type: int32 + unit: bit/s + volatile: false + CYPHAL_ENABLE: + default: 1 + description: + long: 0 - Cyphal disabled. 1 - Enables Cyphal + short: Cyphal + reboot_required: true + type: boolean + volatile: false + CYPHAL_ID: + default: 1 + description: + long: Read the specs at http://uavcan.org to learn more about Node ID. + short: Cyphal Node ID + max: 125 + min: -1 + reboot_required: true + type: int32 + volatile: false + UCAN1_ACTR_PUB: + default: -1 + description: + short: actuator_outputs uORB over Cyphal publication port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_BMS_BP_SUB: + default: -1 + description: + short: UDRAL battery parameters subscription port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_BMS_BS_SUB: + default: -1 + description: + short: UDRAL battery status subscription port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_BMS_ES_SUB: + default: -1 + description: + short: UDRAL battery energy source subscription port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_ESC0_SUB: + default: -1 + description: + short: ESC 0 subscription port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_ESC_PUB: + default: -1 + description: + short: Cyphal ESC publication port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_GPS0_SUB: + default: -1 + description: + short: GPS 0 subscription port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_GPS1_SUB: + default: -1 + description: + short: GPS 1 subscription port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_GPS_PUB: + default: -1 + description: + short: Cyphal GPS publication port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_LG_BMS_SUB: + default: -1 + description: + short: Cyphal leagcy battery port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_SERVO_PUB: + default: -1 + description: + short: Cyphal Servo publication port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_UORB_GPS: + default: -1 + description: + short: sensor_gps uORB over Cyphal subscription port ID + max: 6143 + min: -1 + type: int32 + volatile: false + UCAN1_UORB_GPS_P: + default: -1 + description: + short: sensor_gps uORB over Cyphal publication port ID + max: 6143 + min: -1 + type: int32 + volatile: false + group: Cyphal diff --git a/src/drivers/cyphal/parameters.c b/src/drivers/cyphal/parameters.c deleted file mode 100644 index d9f8ea9b38d5..000000000000 --- a/src/drivers/cyphal/parameters.c +++ /dev/null @@ -1,190 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Cyphal - * - * 0 - Cyphal disabled. - * 1 - Enables Cyphal - * - * @boolean - * @reboot_required true - * @group Cyphal - */ -PARAM_DEFINE_INT32(CYPHAL_ENABLE, 1); - -/** - * Cyphal Node ID. - * - * Read the specs at http://uavcan.org to learn more about Node ID. - * - * @min -1 - * @max 125 - * @reboot_required true - * @group Cyphal - */ -PARAM_DEFINE_INT32(CYPHAL_ID, 1); - -/** - * UAVCAN/CAN v1 bus bitrate. - * - * @unit bit/s - * @min 20000 - * @max 1000000 - * @reboot_required true - * @group Cyphal - */ -PARAM_DEFINE_INT32(CYPHAL_BAUD, 1000000); - -/* Subscription port ID, -1 will be treated as unset */ - -/** - * ESC 0 subscription port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_ESC0_SUB, -1); - -/** - * GPS 0 subscription port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_GPS0_SUB, -1); - -/** - * GPS 1 subscription port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_GPS1_SUB, -1); - -/** - * UDRAL battery energy source subscription port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_BMS_ES_SUB, -1); - -/** - * UDRAL battery status subscription port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_BMS_BS_SUB, -1); - -/** - * UDRAL battery parameters subscription port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_BMS_BP_SUB, -1); - -/** - * Cyphal leagcy battery port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_LG_BMS_SUB, -1); - - -/** - * sensor_gps uORB over Cyphal subscription port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_UORB_GPS, -1); - - -/** - * sensor_gps uORB over Cyphal publication port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_UORB_GPS_P, -1); - -// Publication Port IDs - -/** - * Cyphal ESC publication port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_ESC_PUB, -1); - -/** - * Cyphal GPS publication port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_GPS_PUB, -1); - -/** - * Cyphal Servo publication port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_SERVO_PUB, -1); - -/** - * actuator_outputs uORB over Cyphal publication port ID. - * - * @min -1 - * @max 6143 - * @group Cyphal - */ -PARAM_DEFINE_INT32(UCAN1_ACTR_PUB, -1); diff --git a/src/drivers/differential_pressure/ets/CMakeLists.txt b/src/drivers/differential_pressure/ets/CMakeLists.txt index 23dc3f26aab6..c34c6d522b04 100644 --- a/src/drivers/differential_pressure/ets/CMakeLists.txt +++ b/src/drivers/differential_pressure/ets/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( ets_airspeed_main.cpp ETSAirspeed.cpp ETSAirspeed.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/differential_pressure/ets/module.yaml b/src/drivers/differential_pressure/ets/module.yaml new file mode 100644 index 000000000000..0d961b35da69 --- /dev/null +++ b/src/drivers/differential_pressure/ets/module.yaml @@ -0,0 +1,11 @@ +module_name: ets +parameters: + - definitions: + SENS_EN_ETSASPD: + default: 0 + description: + short: Eagle Tree airspeed sensor (external I2C) + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/differential_pressure/ets/parameters.c b/src/drivers/differential_pressure/ets/parameters.c deleted file mode 100644 index 5a0f7728ffbf..000000000000 --- a/src/drivers/differential_pressure/ets/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Eagle Tree airspeed sensor (external I2C) - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_ETSASPD, 0); diff --git a/src/drivers/differential_pressure/ms4515/CMakeLists.txt b/src/drivers/differential_pressure/ms4515/CMakeLists.txt index e3e1d1ad5587..824f720f6a4b 100644 --- a/src/drivers/differential_pressure/ms4515/CMakeLists.txt +++ b/src/drivers/differential_pressure/ms4515/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( ms4515_main.cpp MS4515.cpp MS4515.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/differential_pressure/ms4515/module.yaml b/src/drivers/differential_pressure/ms4515/module.yaml new file mode 100644 index 000000000000..e4c9d59137d4 --- /dev/null +++ b/src/drivers/differential_pressure/ms4515/module.yaml @@ -0,0 +1,11 @@ +module_name: ms4515 +parameters: + - definitions: + SENS_EN_MS4515: + default: 0 + description: + short: TE MS4515 differential pressure sensor (external I2C) + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/differential_pressure/ms4515/parameters.c b/src/drivers/differential_pressure/ms4515/parameters.c deleted file mode 100644 index 25337376a3e7..000000000000 --- a/src/drivers/differential_pressure/ms4515/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * TE MS4515 differential pressure sensor (external I2C) - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_MS4515, 0); diff --git a/src/drivers/differential_pressure/ms4525do/CMakeLists.txt b/src/drivers/differential_pressure/ms4525do/CMakeLists.txt index 49bf83e18117..1c5fbdbc9de0 100644 --- a/src/drivers/differential_pressure/ms4525do/CMakeLists.txt +++ b/src/drivers/differential_pressure/ms4525do/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( ms4525do_main.cpp MS4525DO.cpp MS4525DO.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/differential_pressure/ms4525do/module.yaml b/src/drivers/differential_pressure/ms4525do/module.yaml new file mode 100644 index 000000000000..04f5140d3566 --- /dev/null +++ b/src/drivers/differential_pressure/ms4525do/module.yaml @@ -0,0 +1,11 @@ +module_name: ms4525do +parameters: + - definitions: + SENS_EN_MS4525DO: + default: 0 + description: + short: TE MS4525DO differential pressure sensor (external I2C) + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/differential_pressure/ms4525do/parameters.c b/src/drivers/differential_pressure/ms4525do/parameters.c deleted file mode 100644 index 86f722ab1904..000000000000 --- a/src/drivers/differential_pressure/ms4525do/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * TE MS4525DO differential pressure sensor (external I2C) - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_MS4525DO, 0); diff --git a/src/drivers/differential_pressure/ms5525dso/CMakeLists.txt b/src/drivers/differential_pressure/ms5525dso/CMakeLists.txt index 1cf253b7aa94..07068576c3f0 100644 --- a/src/drivers/differential_pressure/ms5525dso/CMakeLists.txt +++ b/src/drivers/differential_pressure/ms5525dso/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( ms5525dso_main.cpp MS5525DSO.cpp MS5525DSO.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/differential_pressure/ms5525dso/module.yaml b/src/drivers/differential_pressure/ms5525dso/module.yaml new file mode 100644 index 000000000000..b12d8f067c62 --- /dev/null +++ b/src/drivers/differential_pressure/ms5525dso/module.yaml @@ -0,0 +1,11 @@ +module_name: ms5525dso +parameters: + - definitions: + SENS_EN_MS5525DS: + default: 0 + description: + short: TE MS5525DSO differential pressure sensor (external I2C) + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/differential_pressure/ms5525dso/parameters.c b/src/drivers/differential_pressure/ms5525dso/parameters.c deleted file mode 100644 index a96d82b981a8..000000000000 --- a/src/drivers/differential_pressure/ms5525dso/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * TE MS5525DSO differential pressure sensor (external I2C) - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_MS5525DS, 0); diff --git a/src/drivers/differential_pressure/sdp3x/CMakeLists.txt b/src/drivers/differential_pressure/sdp3x/CMakeLists.txt index f0e626485ddc..c391c0ec02d7 100644 --- a/src/drivers/differential_pressure/sdp3x/CMakeLists.txt +++ b/src/drivers/differential_pressure/sdp3x/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( sdp3x_main.cpp SDP3X.cpp SDP3X.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/differential_pressure/sdp3x/module.yaml b/src/drivers/differential_pressure/sdp3x/module.yaml new file mode 100644 index 000000000000..196fec3eab84 --- /dev/null +++ b/src/drivers/differential_pressure/sdp3x/module.yaml @@ -0,0 +1,11 @@ +module_name: sdp3x +parameters: + - definitions: + SENS_EN_SDP3X: + default: 0 + description: + short: Sensirion SDP3X differential pressure sensor (external I2C) + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/differential_pressure/sdp3x/parameters.c b/src/drivers/differential_pressure/sdp3x/parameters.c deleted file mode 100644 index 47f26836ce68..000000000000 --- a/src/drivers/differential_pressure/sdp3x/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Sensirion SDP3X differential pressure sensor (external I2C) - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_SDP3X, 0); diff --git a/src/drivers/distance_sensor/cm8jl65/module.yaml b/src/drivers/distance_sensor/cm8jl65/module.yaml index 886dce7e3a78..ff59caa2dcfb 100644 --- a/src/drivers/distance_sensor/cm8jl65/module.yaml +++ b/src/drivers/distance_sensor/cm8jl65/module.yaml @@ -1,26 +1,24 @@ module_name: Lanbao PSK-CM8JL65-CC5 serial_config: - - command: cm8jl65 start -d ${SERIAL_DEV} -R p:SENS_CM8JL65_R_0 - port_config_param: - name: SENS_CM8JL65_CFG - group: Sensors - + - command: cm8jl65 start -d ${SERIAL_DEV} -R p:SENS_CM8JL65_R_0 + port_config_param: + name: SENS_CM8JL65_CFG + group: Sensors parameters: - - group: Sensors - definitions: - SENS_CM8JL65_R_0: - description: - short: Distance Sensor Rotation - long: | - Distance Sensor Rotation as MAV_SENSOR_ORIENTATION enum - - type: enum - values: - 25: ROTATION_DOWNWARD_FACING - 24: ROTATION_UPWARD_FACING - 12: ROTATION_BACKWARD_FACING - 0: ROTATION_FORWARD_FACING - 6: ROTATION_LEFT_FACING - 2: ROTATION_RIGHT_FACING - reboot_required: true - default: 25 + - group: Sensors + definitions: + SENS_CM8JL65_R_0: + description: + short: Distance Sensor Rotation + long: | + Distance Sensor Rotation as MAV_SENSOR_ORIENTATION enum + type: enum + values: + 25: ROTATION_DOWNWARD_FACING + 24: ROTATION_UPWARD_FACING + 12: ROTATION_BACKWARD_FACING + 0: ROTATION_FORWARD_FACING + 6: ROTATION_LEFT_FACING + 2: ROTATION_RIGHT_FACING + reboot_required: true + default: 25 diff --git a/src/drivers/distance_sensor/leddar_one/module.yaml b/src/drivers/distance_sensor/leddar_one/module.yaml index 6c70a1af528b..e387d4d5d8a1 100644 --- a/src/drivers/distance_sensor/leddar_one/module.yaml +++ b/src/drivers/distance_sensor/leddar_one/module.yaml @@ -1,6 +1,6 @@ module_name: LeddarOne Rangefinder serial_config: - - command: leddar_one start -d ${SERIAL_DEV} - port_config_param: - name: SENS_LEDDAR1_CFG - group: Sensors + - command: leddar_one start -d ${SERIAL_DEV} + port_config_param: + name: SENS_LEDDAR1_CFG + group: Sensors diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/CMakeLists.txt b/src/drivers/distance_sensor/lightware_laser_i2c/CMakeLists.txt index 657ffa105efb..d58a109600ae 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/CMakeLists.txt +++ b/src/drivers/distance_sensor/lightware_laser_i2c/CMakeLists.txt @@ -35,6 +35,8 @@ px4_add_module( MAIN lightware_laser_i2c SRCS lightware_laser_i2c.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers_rangefinder ) diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/module.yaml b/src/drivers/distance_sensor/lightware_laser_i2c/module.yaml new file mode 100644 index 000000000000..23e3c3add968 --- /dev/null +++ b/src/drivers/distance_sensor/lightware_laser_i2c/module.yaml @@ -0,0 +1,21 @@ +module_name: lightware_laser_i2c +parameters: + - definitions: + SENS_EN_SF1XX: + default: 0 + description: + short: Lightware SF1xx/SF20/LW20 laser rangefinder (i2c) + max: 6 + min: 0 + reboot_required: true + type: enum + values: + 0: Disabled + 1: SF10/a + 2: SF10/b + 3: SF10/c + 4: SF11/c + 5: SF/LW20/b + 6: SF/LW20/c + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c b/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c deleted file mode 100644 index c417efbe9e48..000000000000 --- a/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c +++ /dev/null @@ -1,49 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Lightware SF1xx/SF20/LW20 laser rangefinder (i2c) - * - * @reboot_required true - * @min 0 - * @max 6 - * @group Sensors - * @value 0 Disabled - * @value 1 SF10/a - * @value 2 SF10/b - * @value 3 SF10/c - * @value 4 SF11/c - * @value 5 SF/LW20/b - * @value 6 SF/LW20/c - */ -PARAM_DEFINE_INT32(SENS_EN_SF1XX, 0); diff --git a/src/drivers/distance_sensor/lightware_laser_serial/module.yaml b/src/drivers/distance_sensor/lightware_laser_serial/module.yaml index 269fe85ffd8c..f54cb5ba8006 100644 --- a/src/drivers/distance_sensor/lightware_laser_serial/module.yaml +++ b/src/drivers/distance_sensor/lightware_laser_serial/module.yaml @@ -1,7 +1,25 @@ module_name: Lightware Laser Rangefinder (serial) serial_config: - - command: lightware_laser_serial start -d ${SERIAL_DEV} - port_config_param: - name: SENS_SF0X_CFG - group: Sensors - + - command: lightware_laser_serial start -d ${SERIAL_DEV} + port_config_param: + name: SENS_SF0X_CFG + group: Sensors +parameters: + - definitions: + SENS_EN_SF0X: + default: 1 + description: + short: Lightware Laser Rangefinder hardware model (serial) + reboot_required: true + type: enum + values: + 1: SF02 + 2: SF10/a + 3: SF10/b + 4: SF10/c + 5: SF11/c + 6: SF30/b + 7: SF30/c + 8: LW20/c + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/lightware_laser_serial/parameters.c b/src/drivers/distance_sensor/lightware_laser_serial/parameters.c deleted file mode 100644 index f8b2c01a8ed4..000000000000 --- a/src/drivers/distance_sensor/lightware_laser_serial/parameters.c +++ /dev/null @@ -1,48 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Lightware Laser Rangefinder hardware model (serial) - * - * @reboot_required true - * @group Sensors - * @value 1 SF02 - * @value 2 SF10/a - * @value 3 SF10/b - * @value 4 SF10/c - * @value 5 SF11/c - * @value 6 SF30/b - * @value 7 SF30/c - * @value 8 LW20/c - */ -PARAM_DEFINE_INT32(SENS_EN_SF0X, 1); diff --git a/src/drivers/distance_sensor/ll40ls/CMakeLists.txt b/src/drivers/distance_sensor/ll40ls/CMakeLists.txt index 659fdb8b20b3..f240392c57d9 100644 --- a/src/drivers/distance_sensor/ll40ls/CMakeLists.txt +++ b/src/drivers/distance_sensor/ll40ls/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS ll40ls.cpp LidarLiteI2C.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers_rangefinder ) diff --git a/src/drivers/distance_sensor/ll40ls/module.yaml b/src/drivers/distance_sensor/ll40ls/module.yaml new file mode 100644 index 000000000000..a97a703f7442 --- /dev/null +++ b/src/drivers/distance_sensor/ll40ls/module.yaml @@ -0,0 +1,17 @@ +module_name: ll40ls +parameters: + - definitions: + SENS_EN_LL40LS: + default: 0 + description: + short: Lidar-Lite (LL40LS) + max: 2 + min: 0 + reboot_required: true + type: enum + values: + 0: Disabled + 1: PWM + 2: I2C + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/ll40ls/parameters.c b/src/drivers/distance_sensor/ll40ls/parameters.c deleted file mode 100644 index 327c3715d166..000000000000 --- a/src/drivers/distance_sensor/ll40ls/parameters.c +++ /dev/null @@ -1,45 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Lidar-Lite (LL40LS) - * - * @reboot_required true - * @min 0 - * @max 2 - * @group Sensors - * @value 0 Disabled - * @value 1 PWM - * @value 2 I2C - */ -PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0); diff --git a/src/drivers/distance_sensor/mappydot/CMakeLists.txt b/src/drivers/distance_sensor/mappydot/CMakeLists.txt index 58625fa8eb0d..fac0cc2bf926 100644 --- a/src/drivers/distance_sensor/mappydot/CMakeLists.txt +++ b/src/drivers/distance_sensor/mappydot/CMakeLists.txt @@ -35,6 +35,8 @@ px4_add_module( MAIN mappydot SRCS MappyDot.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers_rangefinder ) diff --git a/src/drivers/distance_sensor/mappydot/module.yaml b/src/drivers/distance_sensor/mappydot/module.yaml new file mode 100644 index 000000000000..1c1db7931e42 --- /dev/null +++ b/src/drivers/distance_sensor/mappydot/module.yaml @@ -0,0 +1,244 @@ +module_name: mappydot +parameters: + - definitions: + SENS_EN_MPDT: + default: 0 + description: + short: Enable Mappydot rangefinder (i2c) + max: 1 + min: 0 + reboot_required: true + type: enum + values: + 0: Disabled + 1: Autodetect + volatile: false + SENS_MPDT0_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 0 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT10_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 10 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT11_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 12 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT1_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 1 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT2_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 2 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT3_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 3 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT4_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 4 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT5_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 5 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT6_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 6 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT7_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 7 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT8_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 8 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MPDT9_ROT: + default: 0 + description: + long: This parameter defines the rotation of the Mappydot sensor relative to the platform. + short: MappyDot Sensor 9 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/mappydot/parameters.c b/src/drivers/distance_sensor/mappydot/parameters.c deleted file mode 100644 index 6fdadaabfcf3..000000000000 --- a/src/drivers/distance_sensor/mappydot/parameters.c +++ /dev/null @@ -1,297 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - - -/** - * Enable Mappydot rangefinder (i2c) - * - * @reboot_required true - * @min 0 - * @max 1 - * @group Sensors - * @value 0 Disabled - * @value 1 Autodetect - */ -PARAM_DEFINE_INT32(SENS_EN_MPDT, 0); - -/** - * MappyDot Sensor 0 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT0_ROT, 0); - -/** - * MappyDot Sensor 1 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT1_ROT, 0); - -/** - * MappyDot Sensor 2 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT2_ROT, 0); - -/** - * MappyDot Sensor 3 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT3_ROT, 0); - -/** - * MappyDot Sensor 4 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT4_ROT, 0); - -/** - * MappyDot Sensor 5 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT5_ROT, 0); - -/** - * MappyDot Sensor 6 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT6_ROT, 0); - -/** - * MappyDot Sensor 7 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT7_ROT, 0); - -/** - * MappyDot Sensor 8 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT8_ROT, 0); - -/** - * MappyDot Sensor 9 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT9_ROT, 0); - -/** - * MappyDot Sensor 10 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT10_ROT, 0); - -/** - * MappyDot Sensor 12 Rotation - * - * This parameter defines the rotation of the Mappydot sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MPDT11_ROT, 0); \ No newline at end of file diff --git a/src/drivers/distance_sensor/mb12xx/CMakeLists.txt b/src/drivers/distance_sensor/mb12xx/CMakeLists.txt index 6413710a330f..88fb5f416edc 100644 --- a/src/drivers/distance_sensor/mb12xx/CMakeLists.txt +++ b/src/drivers/distance_sensor/mb12xx/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( -Wno-cast-align # TODO: fix and enable SRCS mb12xx.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers_rangefinder ) diff --git a/src/drivers/distance_sensor/mb12xx/module.yaml b/src/drivers/distance_sensor/mb12xx/module.yaml new file mode 100644 index 000000000000..76ac1a1f76d6 --- /dev/null +++ b/src/drivers/distance_sensor/mb12xx/module.yaml @@ -0,0 +1,239 @@ +module_name: mb12xx +parameters: + - definitions: + SENS_EN_MB12XX: + default: 0 + description: + short: Maxbotix Sonar (mb12xx) + reboot_required: true + type: boolean + volatile: false + SENS_MB12_0_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 0 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_10_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 10 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_11_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 12 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_1_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 1 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_2_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 2 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_3_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 3 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_4_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 4 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_5_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 5 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_6_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 6 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_7_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 7 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_8_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 8 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + SENS_MB12_9_ROT: + default: 0 + description: + long: This parameter defines the rotation of the sensor relative to the platform. + short: MaxBotix MB12XX Sensor 9 Rotation + max: 7 + min: 0 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/mb12xx/parameters.c b/src/drivers/distance_sensor/mb12xx/parameters.c deleted file mode 100644 index 53a53276e38c..000000000000 --- a/src/drivers/distance_sensor/mb12xx/parameters.c +++ /dev/null @@ -1,294 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Maxbotix Sonar (mb12xx) - * - * @reboot_required true - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_MB12XX, 0); - -/** - * MaxBotix MB12XX Sensor 0 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_0_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 1 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_1_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 2 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_2_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 3 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_3_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 4 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_4_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 5 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_5_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 6 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_6_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 7 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_7_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 8 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_8_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 9 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_9_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 10 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_10_ROT, 0); - -/** - * MaxBotix MB12XX Sensor 12 Rotation - * - * This parameter defines the rotation of the sensor relative to the platform. - * - * @reboot_required true - * @min 0 - * @max 7 - * @group Sensors - * - * @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° - */ -PARAM_DEFINE_INT32(SENS_MB12_11_ROT, 0); \ No newline at end of file diff --git a/src/drivers/distance_sensor/pga460/CMakeLists.txt b/src/drivers/distance_sensor/pga460/CMakeLists.txt index d95a0500a8e2..30f589281194 100644 --- a/src/drivers/distance_sensor/pga460/CMakeLists.txt +++ b/src/drivers/distance_sensor/pga460/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( MAIN pga460 SRCS pga460.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers_rangefinder ) diff --git a/src/drivers/distance_sensor/pga460/module.yaml b/src/drivers/distance_sensor/pga460/module.yaml new file mode 100644 index 000000000000..667c3d93806f --- /dev/null +++ b/src/drivers/distance_sensor/pga460/module.yaml @@ -0,0 +1,11 @@ +module_name: pga460 +parameters: + - definitions: + SENS_EN_PGA460: + default: 0 + description: + short: PGA460 Ultrasonic driver (PGA460) + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/pga460/parameters.c b/src/drivers/distance_sensor/pga460/parameters.c deleted file mode 100644 index ce095963a8e4..000000000000 --- a/src/drivers/distance_sensor/pga460/parameters.c +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * PGA460 Ultrasonic driver (PGA460) - * - * @reboot_required true - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_PGA460, 0); diff --git a/src/drivers/distance_sensor/srf05/CMakeLists.txt b/src/drivers/distance_sensor/srf05/CMakeLists.txt index 5211d23fbd08..63f83755bd2f 100644 --- a/src/drivers/distance_sensor/srf05/CMakeLists.txt +++ b/src/drivers/distance_sensor/srf05/CMakeLists.txt @@ -36,6 +36,8 @@ px4_add_module( COMPILE_FLAGS SRCS SRF05.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers_rangefinder ) diff --git a/src/drivers/distance_sensor/srf05/module.yaml b/src/drivers/distance_sensor/srf05/module.yaml new file mode 100644 index 000000000000..ba5d41f49d9e --- /dev/null +++ b/src/drivers/distance_sensor/srf05/module.yaml @@ -0,0 +1,11 @@ +module_name: srf05 +parameters: + - definitions: + SENS_EN_SR05: + default: 0 + description: + short: HY-SRF05 / HC-SR05 + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/srf05/parameters.c b/src/drivers/distance_sensor/srf05/parameters.c deleted file mode 100644 index ac0f108c5184..000000000000 --- a/src/drivers/distance_sensor/srf05/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * HY-SRF05 / HC-SR05 - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_SR05, 0); diff --git a/src/drivers/distance_sensor/teraranger/CMakeLists.txt b/src/drivers/distance_sensor/teraranger/CMakeLists.txt index 5c0903d1fb0b..73ef48592420 100644 --- a/src/drivers/distance_sensor/teraranger/CMakeLists.txt +++ b/src/drivers/distance_sensor/teraranger/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( teraranger_main.cpp TERARANGER.cpp TERARANGER.hpp + MODULE_CONFIG + module.yaml DEPENDS drivers_rangefinder px4_work_queue diff --git a/src/drivers/distance_sensor/teraranger/module.yaml b/src/drivers/distance_sensor/teraranger/module.yaml new file mode 100644 index 000000000000..8c86be1998d7 --- /dev/null +++ b/src/drivers/distance_sensor/teraranger/module.yaml @@ -0,0 +1,20 @@ +module_name: teraranger +parameters: + - definitions: + SENS_EN_TRANGER: + default: 0 + description: + short: TeraRanger Rangefinder (i2c) + max: 3 + min: 0 + reboot_required: true + type: enum + values: + 0: Disabled + 1: Autodetect + 2: TROne + 3: TREvo60m + 4: TREvo600Hz + 5: TREvo3m + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/teraranger/parameters.c b/src/drivers/distance_sensor/teraranger/parameters.c deleted file mode 100644 index 56253fe7a98c..000000000000 --- a/src/drivers/distance_sensor/teraranger/parameters.c +++ /dev/null @@ -1,48 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * TeraRanger Rangefinder (i2c) - * - * @reboot_required true - * @min 0 - * @max 3 - * @group Sensors - * @value 0 Disabled - * @value 1 Autodetect - * @value 2 TROne - * @value 3 TREvo60m - * @value 4 TREvo600Hz - * @value 5 TREvo3m - */ -PARAM_DEFINE_INT32(SENS_EN_TRANGER, 0); diff --git a/src/drivers/distance_sensor/tfmini/module.yaml b/src/drivers/distance_sensor/tfmini/module.yaml index 770cbe979c37..506c9cd3df23 100644 --- a/src/drivers/distance_sensor/tfmini/module.yaml +++ b/src/drivers/distance_sensor/tfmini/module.yaml @@ -1,7 +1,6 @@ module_name: Benewake TFmini Rangefinder serial_config: - - command: tfmini start -d ${SERIAL_DEV} - port_config_param: - name: SENS_TFMINI_CFG - group: Sensors - + - command: tfmini start -d ${SERIAL_DEV} + port_config_param: + name: SENS_TFMINI_CFG + group: Sensors diff --git a/src/drivers/distance_sensor/ulanding_radar/module.yaml b/src/drivers/distance_sensor/ulanding_radar/module.yaml index 73dc25174921..fb34ca429d15 100644 --- a/src/drivers/distance_sensor/ulanding_radar/module.yaml +++ b/src/drivers/distance_sensor/ulanding_radar/module.yaml @@ -1,6 +1,6 @@ module_name: uLanding Radar serial_config: - - command: ulanding_radar start -d ${SERIAL_DEV} - port_config_param: - name: SENS_ULAND_CFG - group: Sensors + - command: ulanding_radar start -d ${SERIAL_DEV} + port_config_param: + name: SENS_ULAND_CFG + group: Sensors diff --git a/src/drivers/distance_sensor/vl53l1x/CMakeLists.txt b/src/drivers/distance_sensor/vl53l1x/CMakeLists.txt index e3564ed36010..31c96a23d7ed 100644 --- a/src/drivers/distance_sensor/vl53l1x/CMakeLists.txt +++ b/src/drivers/distance_sensor/vl53l1x/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( SRCS vl53l1x.cpp vl53l1x.hpp + MODULE_CONFIG + module.yaml DEPENDS drivers_rangefinder px4_work_queue diff --git a/src/drivers/distance_sensor/vl53l1x/module.yaml b/src/drivers/distance_sensor/vl53l1x/module.yaml new file mode 100644 index 000000000000..619e0f05897d --- /dev/null +++ b/src/drivers/distance_sensor/vl53l1x/module.yaml @@ -0,0 +1,11 @@ +module_name: vl53l1x +parameters: + - definitions: + SENS_EN_VL53L1X: + default: 0 + description: + short: VL53L1X Distance Sensor + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/distance_sensor/vl53l1x/params.c b/src/drivers/distance_sensor/vl53l1x/params.c deleted file mode 100644 index 8092b9465ee0..000000000000 --- a/src/drivers/distance_sensor/vl53l1x/params.c +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * VL53L1X Distance Sensor - * - * @reboot_required true - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_VL53L1X, 0); diff --git a/src/drivers/dshot/module.yaml b/src/drivers/dshot/module.yaml index 850aaf69dfa4..ca43ef0b7b54 100644 --- a/src/drivers/dshot/module.yaml +++ b/src/drivers/dshot/module.yaml @@ -1,84 +1,83 @@ module_name: DShot Driver serial_config: - - command: dshot telemetry ${SERIAL_DEV} - port_config_param: - name: DSHOT_TEL_CFG - group: DShot - + - command: dshot telemetry ${SERIAL_DEV} + port_config_param: + name: DSHOT_TEL_CFG + group: DShot parameters: - - group: DShot - definitions: - DSHOT_CONFIG: - description: - short: Configure DShot - long: | - This enables/disables DShot. The different modes define different - speeds, for example DShot150 = 150kb/s. Not all ESCs support all modes. + - group: DShot + definitions: + DSHOT_CONFIG: + description: + short: Configure DShot + long: | + This enables/disables DShot. The different modes define different + speeds, for example DShot150 = 150kb/s. Not all ESCs support all modes. - Note: this enables DShot on the FMU outputs. For boards with an IO it is the - AUX outputs. - type: enum - values: - 0: Disable (use PWM/Oneshot) - 150: DShot150 - 300: DShot300 - 600: DShot600 - 1200: DShot1200 - reboot_required: true - default: 0 - DSHOT_MIN: - description: - short: Minimum DShot Motor Output - long: | - Minimum Output Value for DShot in percent. The value depends on the ESC. Make - sure to set this high enough so that the motors are always spinning while - armed. - type: float - unit: '%' - min: 0 - max: 1 - decimal: 2 - increment: 0.01 - default: 0.055 - DSHOT_3D_ENABLE: - description: - short: Allows for 3d mode when using DShot and suitable mixer - long: | - WARNING: ESC must be configured for 3D mode, and DSHOT_MIN set to 0. - This splits the throttle ranges in two. - Direction 1) 48 is the slowest, 1047 is the fastest. - Direction 2) 1049 is the slowest, 2047 is the fastest. - When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. - type: boolean - default: 0 - DSHOT_3D_DEAD_H: - description: - short: DSHOT 3D deadband high - long: | - When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. - This value is with respect to the mixer_module range (0-1999), not the DSHOT values. - type: int32 - min: 1000 - max: 1999 - default: 1000 - DSHOT_3D_DEAD_L: - description: - short: DSHOT 3D deadband low - long: | - When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. - This value is with respect to the mixer_module range (0-1999), not the DSHOT values. - type: int32 - min: 0 - max: 1000 - default: 1000 - MOT_POLE_COUNT: # only used by dshot so far, so keep it under the dshot group - description: - short: Number of magnetic poles of the motors - long: | - Specify the number of magnetic poles of the motors. - It is required to compute the RPM value from the eRPM returned with the ESC telemetry. + Note: this enables DShot on the FMU outputs. For boards with an IO it is the + AUX outputs. + type: enum + values: + 0: Disable (use PWM/Oneshot) + 150: DShot150 + 300: DShot300 + 600: DShot600 + 1200: DShot1200 + reboot_required: true + default: 0 + DSHOT_MIN: + description: + short: Minimum DShot Motor Output + long: | + Minimum Output Value for DShot in percent. The value depends on the ESC. Make + sure to set this high enough so that the motors are always spinning while + armed. + type: float + unit: '%' + min: 0 + max: 1 + decimal: 2 + increment: 0.01 + default: 0.055 + DSHOT_3D_ENABLE: + description: + short: Allows for 3d mode when using DShot and suitable mixer + long: | + WARNING: ESC must be configured for 3D mode, and DSHOT_MIN set to 0. + This splits the throttle ranges in two. + Direction 1) 48 is the slowest, 1047 is the fastest. + Direction 2) 1049 is the slowest, 2047 is the fastest. + When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. + type: boolean + default: 0 + DSHOT_3D_DEAD_H: + description: + short: DSHOT 3D deadband high + long: | + When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. + This value is with respect to the mixer_module range (0-1999), not the DSHOT values. + type: int32 + min: 1000 + max: 1999 + default: 1000 + DSHOT_3D_DEAD_L: + description: + short: DSHOT 3D deadband low + long: | + When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. + This value is with respect to the mixer_module range (0-1999), not the DSHOT values. + type: int32 + min: 0 + max: 1000 + default: 1000 + MOT_POLE_COUNT: # only used by dshot so far, so keep it under the dshot group + description: + short: Number of magnetic poles of the motors + long: | + Specify the number of magnetic poles of the motors. + It is required to compute the RPM value from the eRPM returned with the ESC telemetry. - Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets). - Typical motors for 5 inch props have 14 poles. - type: int32 - default: 14 + Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets). + Typical motors for 5 inch props have 14 poles. + type: int32 + default: 14 diff --git a/src/drivers/gps/module.yaml b/src/drivers/gps/module.yaml index 484e434d5881..24d12e8c73b6 100644 --- a/src/drivers/gps/module.yaml +++ b/src/drivers/gps/module.yaml @@ -1,16 +1,150 @@ -module_name: GPS +module_name: gps serial_config: - # secondary gps must be first - - command: set DUAL_GPS_ARGS "-e ${SERIAL_DEV} -g p:${BAUD_PARAM}" - port_config_param: - name: GPS_2_CONFIG - group: GPS - label: Secondary GPS - - - command: gps start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} ${DUAL_GPS_ARGS} - port_config_param: - name: GPS_1_CONFIG - group: GPS - default: GPS1 - label: Main GPS - + # secondary gps must be first + - command: set DUAL_GPS_ARGS "-e ${SERIAL_DEV} -g p:${BAUD_PARAM}" + port_config_param: + name: GPS_2_CONFIG + group: GPS + label: Secondary GPS + - command: gps start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} ${DUAL_GPS_ARGS} + port_config_param: + name: GPS_1_CONFIG + group: GPS + default: GPS1 + label: Main GPS +parameters: + - definitions: + GPS_1_GNSS: + bit: + 0: GPS (with QZSS) + 1: SBAS + 2: Galileo + 3: BeiDou + 4: GLONASS + default: 0 + description: + long: 'This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver''s documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver''s default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS' + short: GNSS Systems for Primary GPS (integer bitmask) + max: 31 + min: 0 + reboot_required: true + type: bitmask + volatile: false + GPS_1_PROTOCOL: + default: 1 + description: + long: Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. + short: Protocol for Main GPS + max: 5 + min: 0 + reboot_required: true + type: enum + values: + 0: Auto detect + 1: u-blox + 2: MTK + 3: Ashtech / Trimble + 4: Emlid Reach + 5: Femtomes + 6: NMEA (generic) + volatile: false + GPS_2_GNSS: + bit: + 0: GPS (with QZSS) + 1: SBAS + 2: Galileo + 3: BeiDou + 4: GLONASS + default: 0 + description: + long: 'This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver''s documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver''s default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS' + short: GNSS Systems for Secondary GPS (integer bitmask) + max: 31 + min: 0 + reboot_required: true + type: bitmask + volatile: false + GPS_2_PROTOCOL: + default: 1 + description: + long: Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. + short: Protocol for Secondary GPS + max: 5 + min: 0 + reboot_required: true + type: enum + values: + 0: Auto detect + 1: u-blox + 2: MTK + 3: Ashtech / Trimble + 4: Emlid Reach + 5: Femtomes + 6: NMEA (generic) + volatile: false + GPS_DUMP_COMM: + default: 0 + description: + long: If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK. + short: Log GPS communication data + max: 2 + min: 0 + type: enum + values: + 0: Disable + 1: Full communication + 2: RTCM output (PPK) + volatile: false + GPS_SAT_INFO: + default: 0 + description: + long: Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK. + short: Enable sat info (if available) + reboot_required: true + type: boolean + volatile: false + GPS_UBX_DYNMODEL: + default: 7 + description: + long: u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment. + short: u-blox GPS dynamic platform model + max: 9 + min: 0 + reboot_required: true + type: enum + values: + 2: stationary + 4: automotive + 6: airborne with <1g acceleration + 7: airborne with <2g acceleration + 8: airborne with <4g acceleration + volatile: false + GPS_UBX_MODE: + default: 0 + description: + long: Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base. Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup. + short: u-blox GPS Mode + max: 1 + min: 0 + reboot_required: true + type: enum + values: + 0: Default + 1: Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base) + 2: Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover) + 3: Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600) + 4: Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600) + volatile: false + GPS_YAW_OFFSET: + decimal: 0 + default: 0.0 + description: + long: Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. + short: Heading/Yaw offset for dual antenna GPS + max: 360 + min: 0 + reboot_required: true + type: float + unit: deg + volatile: false + group: GPS diff --git a/src/drivers/gps/params.c b/src/drivers/gps/params.c deleted file mode 100644 index 25a0cb293461..000000000000 --- a/src/drivers/gps/params.c +++ /dev/null @@ -1,233 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Log GPS communication data - * - * If this is set to 1, all GPS communication data will be published via uORB, - * and written to the log file as gps_dump message. - * - * If this is set to 2, the main GPS is configured to output RTCM data, - * which is then logged as gps_dump and can be used for PPK. - * - * @min 0 - * @max 2 - * @value 0 Disable - * @value 1 Full communication - * @value 2 RTCM output (PPK) - * @group GPS - */ -PARAM_DEFINE_INT32(GPS_DUMP_COMM, 0); - -/** - * u-blox GPS dynamic platform model - * - * u-blox receivers support different dynamic platform models to adjust the navigation engine to - * the expected application environment. - * - * @min 0 - * @max 9 - * @value 2 stationary - * @value 4 automotive - * @value 6 airborne with <1g acceleration - * @value 7 airborne with <2g acceleration - * @value 8 airborne with <4g acceleration - * - * @reboot_required true - * - * @group GPS - */ -PARAM_DEFINE_INT32(GPS_UBX_DYNMODEL, 7); - -/** - * Enable sat info (if available) - * - * Enable publication of satellite info (ORB_ID(satellite_info)) if possible. - * Not available on MTK. - * - * @boolean - * @reboot_required true - * @group GPS - */ -PARAM_DEFINE_INT32(GPS_SAT_INFO, 0); - -/** - * u-blox GPS Mode - * - * Select the u-blox configuration setup. Most setups will use the default, including RTK and - * dual GPS without heading. - * - * The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output - * heading information, whereas the secondary will act as moving base. - * Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the - * F9P units are connected to each other. - * Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. - * RTK is still possible with this setup. - * - * @min 0 - * @max 1 - * @value 0 Default - * @value 1 Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base) - * @value 2 Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover) - * @value 3 Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600) - * @value 4 Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600) - * - * @reboot_required true - * @group GPS - */ -PARAM_DEFINE_INT32(GPS_UBX_MODE, 0); - - -/** - * Heading/Yaw offset for dual antenna GPS - * - * Heading offset angle for dual antenna GPS setups that support heading estimation. - * - * Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover antenna is in - * front. The offset angle increases clockwise. - * - * Set this to 90 if the rover antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. - * - * @min 0 - * @max 360 - * @unit deg - * @reboot_required true - * @decimal 0 - * - * @group GPS - */ -PARAM_DEFINE_FLOAT(GPS_YAW_OFFSET, 0.f); - -/** - * Protocol for Main GPS - * - * Select the GPS protocol over serial. - * - * Auto-detection will probe all protocols, and thus is a bit slower. - * - * @min 0 - * @max 5 - * @value 0 Auto detect - * @value 1 u-blox - * @value 2 MTK - * @value 3 Ashtech / Trimble - * @value 4 Emlid Reach - * @value 5 Femtomes - * @value 6 NMEA (generic) - * - * @reboot_required true - * @group GPS - */ -PARAM_DEFINE_INT32(GPS_1_PROTOCOL, 1); - -/** - * Protocol for Secondary GPS - * - * Select the GPS protocol over serial. - * - * Auto-detection will probe all protocols, and thus is a bit slower. - * - * @min 0 - * @max 5 - * @value 0 Auto detect - * @value 1 u-blox - * @value 2 MTK - * @value 3 Ashtech / Trimble - * @value 4 Emlid Reach - * @value 5 Femtomes - * @value 6 NMEA (generic) - * - * @reboot_required true - * @group GPS - */ -PARAM_DEFINE_INT32(GPS_2_PROTOCOL, 1); - -/** - * GNSS Systems for Primary GPS (integer bitmask) - * - * This integer bitmask controls the set of GNSS systems used by the receiver. Check your - * receiver's documentation on how many systems are supported to be used in parallel. - * - * Currently this functionality is just implemented for u-blox receivers. - * - * When no bits are set, the receiver's default configuration should be used. - * - * Set bits true to enable: - * 0 : Use GPS (with QZSS) - * 1 : Use SBAS (multiple GPS augmentation systems) - * 2 : Use Galileo - * 3 : Use BeiDou - * 4 : Use GLONASS - * - * @min 0 - * @max 31 - * @bit 0 GPS (with QZSS) - * @bit 1 SBAS - * @bit 2 Galileo - * @bit 3 BeiDou - * @bit 4 GLONASS - * - * @reboot_required true - * @group GPS - */ -PARAM_DEFINE_INT32(GPS_1_GNSS, 0); - -/** - * GNSS Systems for Secondary GPS (integer bitmask) - * - * This integer bitmask controls the set of GNSS systems used by the receiver. Check your - * receiver's documentation on how many systems are supported to be used in parallel. - * - * Currently this functionality is just implemented for u-blox receivers. - * - * When no bits are set, the receiver's default configuration should be used. - * - * Set bits true to enable: - * 0 : Use GPS (with QZSS) - * 1 : Use SBAS (multiple GPS augmentation systems) - * 2 : Use Galileo - * 3 : Use BeiDou - * 4 : Use GLONASS - * - * @min 0 - * @max 31 - * @bit 0 GPS (with QZSS) - * @bit 1 SBAS - * @bit 2 Galileo - * @bit 3 BeiDou - * @bit 4 GLONASS - * - * @reboot_required true - * @group GPS - */ -PARAM_DEFINE_INT32(GPS_2_GNSS, 0); diff --git a/src/drivers/heater/CMakeLists.txt b/src/drivers/heater/CMakeLists.txt index 6f1fe2e249a1..2cc694d3da04 100644 --- a/src/drivers/heater/CMakeLists.txt +++ b/src/drivers/heater/CMakeLists.txt @@ -36,4 +36,6 @@ px4_add_module( COMPILE_FLAGS SRCS heater.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/drivers/heater/heater_params.c b/src/drivers/heater/heater_params.c deleted file mode 100644 index 151f9f3eafb5..000000000000 --- a/src/drivers/heater/heater_params.c +++ /dev/null @@ -1,97 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2018-19 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file heater_params.c - * Heater parameters. - * - * @author Mark Sauder - * @author Alex Klimaj - * @author Jake Dahl - */ - -/** - * Target IMU device ID to regulate temperature. - * - * @category system - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_TEMP_ID, 0); - -/** - * Target IMU temperature. - * - * @category system - * @group Sensors - * @unit celcius - * @min 0 - * @max 85.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(SENS_IMU_TEMP, 55.0f); - -/** - * IMU heater controller feedforward value. - * - * @category system - * @group Sensors - * @unit % - * @min 0 - * @max 1.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(SENS_IMU_TEMP_FF, 0.05f); - -/** - * IMU heater controller integrator gain value. - * - * @category system - * @group Sensors - * @unit us/C - * @min 0 - * @max 1.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(SENS_IMU_TEMP_I, 0.025f); - -/** - * IMU heater controller proportional gain value. - * - * @category system - * @group Sensors - * @unit us/C - * @min 0 - * @max 2.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(SENS_IMU_TEMP_P, 1.0f); diff --git a/src/drivers/heater/module.yaml b/src/drivers/heater/module.yaml new file mode 100644 index 000000000000..c54277ffdd3c --- /dev/null +++ b/src/drivers/heater/module.yaml @@ -0,0 +1,55 @@ +module_name: heater +parameters: + - definitions: + SENS_IMU_TEMP: + category: System + decimal: 3 + default: 55.0 + description: + short: Target IMU temperature + max: 85.0 + min: 0 + type: float + unit: celcius + volatile: false + SENS_IMU_TEMP_FF: + category: System + decimal: 3 + default: 0.05 + description: + short: IMU heater controller feedforward value + max: 1.0 + min: 0 + type: float + unit: '%' + volatile: false + SENS_IMU_TEMP_I: + category: System + decimal: 3 + default: 0.025 + description: + short: IMU heater controller integrator gain value + max: 1.0 + min: 0 + type: float + unit: us/C + volatile: false + SENS_IMU_TEMP_P: + category: System + decimal: 3 + default: 1.0 + description: + short: IMU heater controller proportional gain value + max: 2.0 + min: 0 + type: float + unit: us/C + volatile: false + SENS_TEMP_ID: + category: System + default: 0 + description: + short: Target IMU device ID to regulate temperature + type: int32 + volatile: false + group: Sensors diff --git a/src/drivers/hygrometer/sht3x/CMakeLists.txt b/src/drivers/hygrometer/sht3x/CMakeLists.txt index 2edf899151a9..9530cbc01bcd 100644 --- a/src/drivers/hygrometer/sht3x/CMakeLists.txt +++ b/src/drivers/hygrometer/sht3x/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS sht3x.cpp sht3x.h + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/hygrometer/sht3x/module.yaml b/src/drivers/hygrometer/sht3x/module.yaml new file mode 100644 index 000000000000..358e942d2097 --- /dev/null +++ b/src/drivers/hygrometer/sht3x/module.yaml @@ -0,0 +1,11 @@ +module_name: sht3x +parameters: + - definitions: + SENS_EN_SHT3X: + default: 0 + description: + short: SHT3x temperature and hygrometer + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/hygrometer/sht3x/sht3x_params.c b/src/drivers/hygrometer/sht3x/sht3x_params.c deleted file mode 100644 index 2d54886f4aee..000000000000 --- a/src/drivers/hygrometer/sht3x/sht3x_params.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * SHT3x temperature and hygrometer - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_SHT3X, 0); diff --git a/src/drivers/imu/analog_devices/adis16448/CMakeLists.txt b/src/drivers/imu/analog_devices/adis16448/CMakeLists.txt index b8f8d690fcf3..43c7110687db 100644 --- a/src/drivers/imu/analog_devices/adis16448/CMakeLists.txt +++ b/src/drivers/imu/analog_devices/adis16448/CMakeLists.txt @@ -42,6 +42,8 @@ px4_add_module( ADIS16448.hpp adis16448_main.cpp Analog_Devices_ADIS16448_registers.hpp + MODULE_CONFIG + module.yaml DEPENDS drivers_accelerometer drivers_gyroscope diff --git a/src/drivers/imu/analog_devices/adis16448/module.yaml b/src/drivers/imu/analog_devices/adis16448/module.yaml new file mode 100644 index 000000000000..bdaca2263674 --- /dev/null +++ b/src/drivers/imu/analog_devices/adis16448/module.yaml @@ -0,0 +1,28 @@ +module_name: adis16448 +parameters: + - definitions: + SENS_EN_ADIS164X: + default: 0 + description: + short: Analog Devices ADIS16448 IMU (external SPI) + max: 1 + min: 0 + reboot_required: true + type: enum + values: + 0: Disabled + 1: Enabled + volatile: false + SENS_OR_ADIS164X: + default: 0 + description: + short: Analog Devices ADIS16448 IMU Orientation(external SPI) + max: 101 + min: 0 + reboot_required: true + type: enum + values: + 0: ROTATION_NONE + 4: ROTATION_YAW_180 + volatile: false + group: Sensors diff --git a/src/drivers/imu/analog_devices/adis16448/parameters.c b/src/drivers/imu/analog_devices/adis16448/parameters.c deleted file mode 100644 index 9b3373609252..000000000000 --- a/src/drivers/imu/analog_devices/adis16448/parameters.c +++ /dev/null @@ -1,56 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Analog Devices ADIS16448 IMU (external SPI) - * - * @reboot_required true - * @min 0 - * @max 1 - * @group Sensors - * @value 0 Disabled - * @value 1 Enabled - */ -PARAM_DEFINE_INT32(SENS_EN_ADIS164X, 0); - -/** - * Analog Devices ADIS16448 IMU Orientation(external SPI) - * - * @reboot_required true - * @min 0 - * @max 101 - * @group Sensors - * @value 0 ROTATION_NONE - * @value 4 ROTATION_YAW_180 - */ -PARAM_DEFINE_INT32(SENS_OR_ADIS164X, 0); diff --git a/src/drivers/irlock/CMakeLists.txt b/src/drivers/irlock/CMakeLists.txt index 7d376f240629..5f9c33fcbfad 100644 --- a/src/drivers/irlock/CMakeLists.txt +++ b/src/drivers/irlock/CMakeLists.txt @@ -37,4 +37,6 @@ px4_add_module( -Wno-cast-align # TODO: fix and enable SRCS irlock.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/drivers/irlock/module.yaml b/src/drivers/irlock/module.yaml new file mode 100644 index 000000000000..71a99cc3ab05 --- /dev/null +++ b/src/drivers/irlock/module.yaml @@ -0,0 +1,11 @@ +module_name: irlock +parameters: + - definitions: + SENS_EN_IRLOCK: + default: 0 + description: + short: IR-LOCK Sensor (external I2C) + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/irlock/parameters.c b/src/drivers/irlock/parameters.c deleted file mode 100644 index 313516579356..000000000000 --- a/src/drivers/irlock/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * IR-LOCK Sensor (external I2C) - * - * @reboot_required true - * @group Sensors - * @boolean - */ -PARAM_DEFINE_INT32(SENS_EN_IRLOCK, 0); diff --git a/src/drivers/linux_pwm_out/module.yaml b/src/drivers/linux_pwm_out/module.yaml index 133e04e155bb..0df31cd5e2c6 100644 --- a/src/drivers/linux_pwm_out/module.yaml +++ b/src/drivers/linux_pwm_out/module.yaml @@ -4,8 +4,8 @@ actuator_output: - param_prefix: PWM_MAIN channel_label: 'Channel' standard_params: - disarmed: { min: 800, max: 2200, default: 900 } - min: { min: 800, max: 1400, default: 1000 } - max: { min: 1600, max: 2200, default: 2000 } - failsafe: { min: 800, max: 2200 } + disarmed: {min: 800, max: 2200, default: 900} + min: {min: 800, max: 1400, default: 1000} + max: {min: 1600, max: 2200, default: 2000} + failsafe: {min: 800, max: 2200} num_channels: 8 diff --git a/src/drivers/migration.sh b/src/drivers/migration.sh new file mode 100755 index 000000000000..7c835f27297f --- /dev/null +++ b/src/drivers/migration.sh @@ -0,0 +1,15 @@ +#!/bin/sh + +HOME="/home/kalyan/Documents/src/PX4-Autopilot/src/drivers" + +for d in $( find -type d ); do + cd $d + count=`ls -1 *.yaml 2>/dev/null | wc -l` + [ $count == 0 ] && cd $HOME && continue + echo $d + [ -f "module.yaml" ] && mv module.yaml module.abc.yaml + yq eval-all '. as $item ireduce ({}; . *+ $item)' *.yaml > module.yaml + rm module.*.yaml + rm *param*.c + cd $HOME +done diff --git a/src/drivers/optical_flow/paa3905/CMakeLists.txt b/src/drivers/optical_flow/paa3905/CMakeLists.txt index 0e699c9b81f5..0d5874d8fbb4 100644 --- a/src/drivers/optical_flow/paa3905/CMakeLists.txt +++ b/src/drivers/optical_flow/paa3905/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( PAA3905.cpp PAA3905.hpp PixArt_PAA3905_Registers.hpp + MODULE_CONFIG + module.yaml DEPENDS conversion drivers__device diff --git a/src/drivers/optical_flow/paa3905/module.yaml b/src/drivers/optical_flow/paa3905/module.yaml new file mode 100644 index 000000000000..06e359fa5e85 --- /dev/null +++ b/src/drivers/optical_flow/paa3905/module.yaml @@ -0,0 +1,11 @@ +module_name: paa3905 +parameters: + - definitions: + SENS_EN_PAA3905: + default: 0 + description: + short: PAA3905 Optical Flow + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/optical_flow/paa3905/parameters.c b/src/drivers/optical_flow/paa3905/parameters.c deleted file mode 100644 index 2646721d9428..000000000000 --- a/src/drivers/optical_flow/paa3905/parameters.c +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * PAA3905 Optical Flow - * - * @reboot_required true - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_PAA3905, 0); diff --git a/src/drivers/optical_flow/paw3902/CMakeLists.txt b/src/drivers/optical_flow/paw3902/CMakeLists.txt index 2bd4380bf907..ae3b7d09844f 100644 --- a/src/drivers/optical_flow/paw3902/CMakeLists.txt +++ b/src/drivers/optical_flow/paw3902/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( PAW3902.cpp PAW3902.hpp PixArt_PAW3902_Registers.hpp + MODULE_CONFIG + module.yaml DEPENDS conversion drivers__device diff --git a/src/drivers/optical_flow/paw3902/module.yaml b/src/drivers/optical_flow/paw3902/module.yaml new file mode 100644 index 000000000000..0d449d3a0bf6 --- /dev/null +++ b/src/drivers/optical_flow/paw3902/module.yaml @@ -0,0 +1,11 @@ +module_name: paw3902 +parameters: + - definitions: + SENS_EN_PAW3902: + default: 0 + description: + short: PAW3902/PAW3903 Optical Flow + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/optical_flow/paw3902/parameters.c b/src/drivers/optical_flow/paw3902/parameters.c deleted file mode 100644 index e2ce1da53365..000000000000 --- a/src/drivers/optical_flow/paw3902/parameters.c +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * PAW3902/PAW3903 Optical Flow - * - * @reboot_required true - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_PAW3902, 0); diff --git a/src/drivers/optical_flow/pmw3901/CMakeLists.txt b/src/drivers/optical_flow/pmw3901/CMakeLists.txt index 33bb3c451120..55da2bb75fae 100644 --- a/src/drivers/optical_flow/pmw3901/CMakeLists.txt +++ b/src/drivers/optical_flow/pmw3901/CMakeLists.txt @@ -38,4 +38,6 @@ px4_add_module( pmw3901_main.cpp PMW3901.cpp PMW3901.hpp + MODULE_CONFIG + module.yaml ) diff --git a/src/drivers/optical_flow/pmw3901/module.yaml b/src/drivers/optical_flow/pmw3901/module.yaml new file mode 100644 index 000000000000..b90255030933 --- /dev/null +++ b/src/drivers/optical_flow/pmw3901/module.yaml @@ -0,0 +1,11 @@ +module_name: pmw3901 +parameters: + - definitions: + SENS_EN_PMW3901: + default: 0 + description: + short: PMW3901 Optical Flow + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/optical_flow/pmw3901/parameters.c b/src/drivers/optical_flow/pmw3901/parameters.c deleted file mode 100644 index 74e9a482663d..000000000000 --- a/src/drivers/optical_flow/pmw3901/parameters.c +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * PMW3901 Optical Flow - * - * @reboot_required true - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_PMW3901, 0); diff --git a/src/drivers/optical_flow/px4flow/CMakeLists.txt b/src/drivers/optical_flow/px4flow/CMakeLists.txt index e3928d80d1a0..e2e6b7d8ad46 100644 --- a/src/drivers/optical_flow/px4flow/CMakeLists.txt +++ b/src/drivers/optical_flow/px4flow/CMakeLists.txt @@ -37,4 +37,6 @@ px4_add_module( -Wno-cast-align # TODO: fix and enable SRCS px4flow.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/drivers/optical_flow/px4flow/module.yaml b/src/drivers/optical_flow/px4flow/module.yaml new file mode 100644 index 000000000000..8a793b6bf824 --- /dev/null +++ b/src/drivers/optical_flow/px4flow/module.yaml @@ -0,0 +1,11 @@ +module_name: px4flow +parameters: + - definitions: + SENS_EN_PX4FLOW: + default: 0 + description: + short: PX4 Flow Optical Flow + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/optical_flow/px4flow/parameters.c b/src/drivers/optical_flow/px4flow/parameters.c deleted file mode 100644 index 485dd08416ec..000000000000 --- a/src/drivers/optical_flow/px4flow/parameters.c +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * PX4 Flow Optical Flow - * - * @reboot_required true - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_PX4FLOW, 0); diff --git a/src/drivers/optical_flow/thoneflow/module.yaml b/src/drivers/optical_flow/thoneflow/module.yaml index 262a23e048bd..c87e7a57a12a 100644 --- a/src/drivers/optical_flow/thoneflow/module.yaml +++ b/src/drivers/optical_flow/thoneflow/module.yaml @@ -1,6 +1,6 @@ module_name: ThoneFlow-3901U optical flow sensor serial_config: - - command: thoneflow start -d ${SERIAL_DEV} - port_config_param: - name: SENS_TFLOW_CFG - group: Sensors \ No newline at end of file + - command: thoneflow start -d ${SERIAL_DEV} + port_config_param: + name: SENS_TFLOW_CFG + group: Sensors diff --git a/src/drivers/osd/atxxxx/CMakeLists.txt b/src/drivers/osd/atxxxx/CMakeLists.txt index 748f6aa4dcce..5bf1d2b5c76d 100644 --- a/src/drivers/osd/atxxxx/CMakeLists.txt +++ b/src/drivers/osd/atxxxx/CMakeLists.txt @@ -35,6 +35,8 @@ px4_add_module( MAIN atxxxx SRCS atxxxx.cpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/drivers/osd/atxxxx/module.yaml b/src/drivers/osd/atxxxx/module.yaml new file mode 100644 index 000000000000..4b0d925d96d0 --- /dev/null +++ b/src/drivers/osd/atxxxx/module.yaml @@ -0,0 +1,16 @@ +module_name: atxxxx +parameters: + - definitions: + OSD_ATXXXX_CFG: + default: 0 + description: + long: Configure the ATXXXX OSD Chip (mounted on the OmnibusF4SD board) and select the transmission standard. + short: Enable/Disable the ATXXX OSD Chip + reboot_required: true + type: enum + values: + 0: Disabled + 1: NTSC + 2: PAL + volatile: false + group: OSD diff --git a/src/drivers/osd/atxxxx/params.c b/src/drivers/osd/atxxxx/params.c deleted file mode 100644 index 1836522c94cb..000000000000 --- a/src/drivers/osd/atxxxx/params.c +++ /dev/null @@ -1,48 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2018-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* Enable/Disable the ATXXX OSD Chip -* -* Configure the ATXXXX OSD Chip (mounted on the OmnibusF4SD board) and -* select the transmission standard. -* -* @value 0 Disabled -* @value 1 NTSC -* @value 2 PAL -* -* @reboot_required true -* @group OSD -* -*/ -PARAM_DEFINE_INT32(OSD_ATXXXX_CFG, 0); diff --git a/src/drivers/pca9685_pwm_out/module.yaml b/src/drivers/pca9685_pwm_out/module.yaml index 8833091e3cc9..81766fbbcbf3 100644 --- a/src/drivers/pca9685_pwm_out/module.yaml +++ b/src/drivers/pca9685_pwm_out/module.yaml @@ -4,8 +4,8 @@ actuator_output: - param_prefix: PCA9685 channel_label: 'Channel' standard_params: - disarmed: { min: 800, max: 2200, default: 900 } - min: { min: 800, max: 1400, default: 1000 } - max: { min: 1600, max: 2200, default: 2000 } - failsafe: { min: 800, max: 2200 } + disarmed: {min: 800, max: 2200, default: 900} + min: {min: 800, max: 1400, default: 1000} + max: {min: 1600, max: 2200, default: 2000} + failsafe: {min: 800, max: 2200} num_channels: 16 diff --git a/src/drivers/power_monitor/ina226/CMakeLists.txt b/src/drivers/power_monitor/ina226/CMakeLists.txt index c80a2bdc7ca5..45f1d519a904 100644 --- a/src/drivers/power_monitor/ina226/CMakeLists.txt +++ b/src/drivers/power_monitor/ina226/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS ina226_main.cpp ina226.cpp + MODULE_CONFIG + module.yaml DEPENDS battery px4_work_queue diff --git a/src/drivers/power_monitor/ina226/ina226_params.c b/src/drivers/power_monitor/ina226/ina226_params.c deleted file mode 100644 index 14038e66e669..000000000000 --- a/src/drivers/power_monitor/ina226/ina226_params.c +++ /dev/null @@ -1,76 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019, 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Enable INA226 Power Monitor - * - * For systems a INA226 Power Monitor, this should be set to true - * - * @group Sensors - * @boolean - * @reboot_required true -*/ -PARAM_DEFINE_INT32(SENS_EN_INA226, 0); - -/** - * INA226 Power Monitor Config - * - * @group Sensors - * @min 0 - * @max 65535 - * @decimal 1 - * @increment 1 -*/ -PARAM_DEFINE_INT32(INA226_CONFIG, 18139); - -/** - * INA226 Power Monitor Max Current - * - * @group Sensors - * @min 0.1 - * @max 200.0 - * @decimal 2 - * @increment 0.1 - */ -PARAM_DEFINE_FLOAT(INA226_CURRENT, 164.0f); - -/** - * INA226 Power Monitor Shunt - * - * @group Sensors - * @min 0.000000001 - * @max 0.1 - * @decimal 10 - * @increment .000000001 - */ -PARAM_DEFINE_FLOAT(INA226_SHUNT, 0.0005f); diff --git a/src/drivers/power_monitor/ina226/module.yaml b/src/drivers/power_monitor/ina226/module.yaml new file mode 100644 index 000000000000..4d4d25a5e185 --- /dev/null +++ b/src/drivers/power_monitor/ina226/module.yaml @@ -0,0 +1,42 @@ +module_name: ina226 +parameters: + - definitions: + INA226_CONFIG: + decimal: 1 + default: 18139 + description: + short: INA226 Power Monitor Config + increment: 1 + max: 65535 + min: 0 + type: int32 + volatile: false + INA226_CURRENT: + decimal: 2 + default: 164.0 + description: + short: INA226 Power Monitor Max Current + increment: 0.1 + max: 200.0 + min: 0.1 + type: float + volatile: false + INA226_SHUNT: + decimal: 10 + default: 0.0005 + description: + short: INA226 Power Monitor Shunt + increment: 1.0e-09 + max: 0.1 + min: 1.0e-09 + type: float + volatile: false + SENS_EN_INA226: + default: 0 + description: + long: For systems a INA226 Power Monitor, this should be set to true + short: Enable INA226 Power Monitor + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/power_monitor/ina228/CMakeLists.txt b/src/drivers/power_monitor/ina228/CMakeLists.txt index 32af49b463cd..ed9bc8036273 100644 --- a/src/drivers/power_monitor/ina228/CMakeLists.txt +++ b/src/drivers/power_monitor/ina228/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS ina228_main.cpp ina228.cpp + MODULE_CONFIG + module.yaml DEPENDS battery px4_work_queue diff --git a/src/drivers/power_monitor/ina228/ina228_params.c b/src/drivers/power_monitor/ina228/ina228_params.c deleted file mode 100644 index 08d55f045617..000000000000 --- a/src/drivers/power_monitor/ina228/ina228_params.c +++ /dev/null @@ -1,76 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Enable INA228 Power Monitor - * - * For systems a INA228 Power Monitor, this should be set to true - * - * @group Sensors - * @boolean - * @reboot_required true -*/ -PARAM_DEFINE_INT32(SENS_EN_INA228, 0); - -/** - * INA228 Power Monitor Config - * - * @group Sensors - * @min 0 - * @max 65535 - * @decimal 1 - * @increment 1 -*/ -PARAM_DEFINE_INT32(INA228_CONFIG, 63779); - -/** - * INA228 Power Monitor Max Current - * - * @group Sensors - * @min 0.1 - * @max 327.68 - * @decimal 2 - * @increment 0.1 - */ -PARAM_DEFINE_FLOAT(INA228_CURRENT, 327.68f); - -/** - * INA228 Power Monitor Shunt - * - * @group Sensors - * @min 0.000000001 - * @max 0.1 - * @decimal 10 - * @increment .000000001 - */ -PARAM_DEFINE_FLOAT(INA228_SHUNT, 0.0005f); diff --git a/src/drivers/power_monitor/ina228/module.yaml b/src/drivers/power_monitor/ina228/module.yaml new file mode 100644 index 000000000000..2956c183ce2d --- /dev/null +++ b/src/drivers/power_monitor/ina228/module.yaml @@ -0,0 +1,42 @@ +module_name: ina228 +parameters: + - definitions: + INA228_CONFIG: + decimal: 1 + default: 63779 + description: + short: INA228 Power Monitor Config + increment: 1 + max: 65535 + min: 0 + type: int32 + volatile: false + INA228_CURRENT: + decimal: 2 + default: 327.68 + description: + short: INA228 Power Monitor Max Current + increment: 0.1 + max: 327.68 + min: 0.1 + type: float + volatile: false + INA228_SHUNT: + decimal: 10 + default: 0.0005 + description: + short: INA228 Power Monitor Shunt + increment: 1.0e-09 + max: 0.1 + min: 1.0e-09 + type: float + volatile: false + SENS_EN_INA228: + default: 0 + description: + long: For systems a INA228 Power Monitor, this should be set to true + short: Enable INA228 Power Monitor + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/power_monitor/ina238/CMakeLists.txt b/src/drivers/power_monitor/ina238/CMakeLists.txt index 311fdad662f1..70ade91a559c 100644 --- a/src/drivers/power_monitor/ina238/CMakeLists.txt +++ b/src/drivers/power_monitor/ina238/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS ina238_main.cpp ina238.cpp + MODULE_CONFIG + module.yaml DEPENDS battery px4_work_queue diff --git a/src/drivers/power_monitor/ina238/ina238_params.c b/src/drivers/power_monitor/ina238/ina238_params.c deleted file mode 100644 index 585cb0151209..000000000000 --- a/src/drivers/power_monitor/ina238/ina238_params.c +++ /dev/null @@ -1,65 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Enable INA238 Power Monitor - * - * For systems a INA238 Power Monitor, this should be set to true - * - * @group Sensors - * @boolean - * @reboot_required true -*/ -PARAM_DEFINE_INT32(SENS_EN_INA238, 0); - -/** - * INA238 Power Monitor Max Current - * - * @group Sensors - * @min 0.1 - * @max 327.68 - * @decimal 2 - * @increment 0.1 - */ -PARAM_DEFINE_FLOAT(INA238_CURRENT, 327.68f); - -/** - * INA238 Power Monitor Shunt - * - * @group Sensors - * @min 0.000000001 - * @max 0.1 - * @decimal 10 - * @increment .000000001 - */ -PARAM_DEFINE_FLOAT(INA238_SHUNT, 0.0003f); diff --git a/src/drivers/power_monitor/ina238/module.yaml b/src/drivers/power_monitor/ina238/module.yaml new file mode 100644 index 000000000000..6c82c0655f2a --- /dev/null +++ b/src/drivers/power_monitor/ina238/module.yaml @@ -0,0 +1,32 @@ +module_name: ina238 +parameters: + - definitions: + INA238_CURRENT: + decimal: 2 + default: 327.68 + description: + short: INA238 Power Monitor Max Current + increment: 0.1 + max: 327.68 + min: 0.1 + type: float + volatile: false + INA238_SHUNT: + decimal: 10 + default: 0.0003 + description: + short: INA238 Power Monitor Shunt + increment: 1.0e-09 + max: 0.1 + min: 1.0e-09 + type: float + volatile: false + SENS_EN_INA238: + default: 0 + description: + long: For systems a INA238 Power Monitor, this should be set to true + short: Enable INA238 Power Monitor + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/drivers/power_monitor/voxlpm/CMakeLists.txt b/src/drivers/power_monitor/voxlpm/CMakeLists.txt index c1043a7d7dc3..ea6d2f05008f 100644 --- a/src/drivers/power_monitor/voxlpm/CMakeLists.txt +++ b/src/drivers/power_monitor/voxlpm/CMakeLists.txt @@ -36,6 +36,8 @@ px4_add_module( SRCS voxlpm.cpp voxlpm_main.cpp + MODULE_CONFIG + module.yaml DEPENDS battery px4_work_queue diff --git a/src/drivers/power_monitor/voxlpm/module.yaml b/src/drivers/power_monitor/voxlpm/module.yaml new file mode 100644 index 000000000000..2b8ec611ed4e --- /dev/null +++ b/src/drivers/power_monitor/voxlpm/module.yaml @@ -0,0 +1,26 @@ +module_name: voxlpm +parameters: + - definitions: + VOXLPM_SHUNT_BAT: + decimal: 10 + default: 0.00063 + description: + short: VOXL Power Monitor Shunt, Battery + increment: 1.0e-09 + max: 0.1 + min: 1.0e-09 + reboot_required: true + type: float + volatile: false + VOXLPM_SHUNT_REG: + decimal: 10 + default: 0.0056 + description: + short: VOXL Power Monitor Shunt, Regulator + increment: 1.0e-09 + max: 0.1 + min: 1.0e-09 + reboot_required: true + type: float + volatile: false + group: Sensors diff --git a/src/drivers/power_monitor/voxlpm/voxlpm_params.c b/src/drivers/power_monitor/voxlpm/voxlpm_params.c deleted file mode 100644 index 5bfee0c07f7c..000000000000 --- a/src/drivers/power_monitor/voxlpm/voxlpm_params.c +++ /dev/null @@ -1,58 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * VOXL Power Monitor Shunt, Battery - * - * @reboot_required true - * - * @min 0.000000001 - * @max 0.1 - * @decimal 10 - * @increment .000000001 - * @group Sensors - */ -PARAM_DEFINE_FLOAT(VOXLPM_SHUNT_BAT, 0.00063f); - -/** - * VOXL Power Monitor Shunt, Regulator - * - * @reboot_required true - * - * @min 0.000000001 - * @max 0.1 - * @decimal 10 - * @increment .000000001 - * @group Sensors - */ -PARAM_DEFINE_FLOAT(VOXLPM_SHUNT_REG, 0.0056f); diff --git a/src/drivers/pps_capture/CMakeLists.txt b/src/drivers/pps_capture/CMakeLists.txt index cf613393f68c..cf3cbc9a8f29 100644 --- a/src/drivers/pps_capture/CMakeLists.txt +++ b/src/drivers/pps_capture/CMakeLists.txt @@ -44,4 +44,6 @@ px4_add_module( -DPARAM_PREFIX="${PARAM_PREFIX}" SRCS PPSCapture.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/drivers/pps_capture/module.yaml b/src/drivers/pps_capture/module.yaml new file mode 100644 index 000000000000..7962877a82ab --- /dev/null +++ b/src/drivers/pps_capture/module.yaml @@ -0,0 +1,12 @@ +module_name: pps_capture +parameters: + - definitions: + PPS_CAP_ENABLE: + default: 0 + description: + long: Enables the PPS capture module. This switches mode of FMU channel 7 to be the PPS input channel. + short: PPS Capture Enable + reboot_required: true + type: boolean + volatile: false + group: GPS diff --git a/src/drivers/pps_capture/pps_capture_params.c b/src/drivers/pps_capture/pps_capture_params.c deleted file mode 100644 index 68442ec83918..000000000000 --- a/src/drivers/pps_capture/pps_capture_params.c +++ /dev/null @@ -1,49 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file pps_capture_params.c - * PPS Capture params - */ -/** - * PPS Capture Enable - * - * Enables the PPS capture module. - * This switches mode of FMU channel 7 to be the - * PPS input channel. - * - * @boolean - * @group GPS - * @reboot_required true - */ -PARAM_DEFINE_INT32(PPS_CAP_ENABLE, 0); diff --git a/src/drivers/pwm_out/module.yaml b/src/drivers/pwm_out/module.yaml index 733276c678d3..0ed34d484719 100644 --- a/src/drivers/pwm_out/module.yaml +++ b/src/drivers/pwm_out/module.yaml @@ -5,29 +5,28 @@ actuator_output: param_prefix: '${PWM_MAIN_OR_AUX}' channel_labels: ['${PWM_MAIN_OR_AUX}', '${PWM_MAIN_OR_AUX_CAP}'] standard_params: - disarmed: { min: 800, max: 2200, default: 900 } - min: { min: 800, max: 1400, default: 1000 } - max: { min: 1600, max: 2200, default: 2000 } - failsafe: { min: 800, max: 2200 } - extra_function_groups: [ pwm_fmu ] + disarmed: {min: 800, max: 2200, default: 900} + min: {min: 800, max: 1400, default: 1000} + max: {min: 1600, max: 2200, default: 2000} + failsafe: {min: 800, max: 2200} + extra_function_groups: [pwm_fmu] pwm_timer_param: description: - short: Output Protocol Configuration for ${label} - long: | - Select which Output Protocol to use for outputs ${label}. + short: Output Protocol Configuration for ${label} + long: | + Select which Output Protocol to use for outputs ${label}. - Custom PWM rates can be used by directly setting any value >0. + Custom PWM rates can be used by directly setting any value >0. type: enum default: 400 values: - -5: DShot150 - -4: DShot300 - -3: DShot600 - -2: DShot1200 - -1: OneShot - 50: PWM 50 Hz - 100: PWM 100 Hz - 200: PWM 200 Hz - 400: PWM 400 Hz + -5: DShot150 + -4: DShot300 + -3: DShot600 + -2: DShot1200 + -1: OneShot + 50: PWM 50 Hz + 100: PWM 100 Hz + 200: PWM 200 Hz + 400: PWM 400 Hz reboot_required: true - diff --git a/src/drivers/pwm_out_sim/module.yaml b/src/drivers/pwm_out_sim/module.yaml new file mode 100644 index 000000000000..8f71bb517710 --- /dev/null +++ b/src/drivers/pwm_out_sim/module.yaml @@ -0,0 +1,10 @@ +module_name: SIM +actuator_output: + show_subgroups_if: 'SYS_HITL>0' + output_groups: + - param_prefix: HIL_ACT + channel_label: Channel + num_channels: 16 + - param_prefix: PWM_MAIN + channel_label: Channel + num_channels: 16 diff --git a/src/drivers/px4io/module.yaml b/src/drivers/px4io/module.yaml index 5b5a1975798c..af8d4c1903ef 100644 --- a/src/drivers/px4io/module.yaml +++ b/src/drivers/px4io/module.yaml @@ -7,23 +7,46 @@ actuator_output: channel_label_module_name_prefix: false timer_config_file: "boards/px4/io-v2/src/timer_config.cpp" standard_params: - disarmed: { min: 800, max: 2200, default: 900 } - min: { min: 800, max: 1400, default: 1000 } - max: { min: 1600, max: 2200, default: 2000 } - failsafe: { min: 800, max: 2200 } + disarmed: {min: 800, max: 2200, default: 900} + min: {min: 800, max: 1400, default: 1000} + max: {min: 1600, max: 2200, default: 2000} + failsafe: {min: 800, max: 2200} pwm_timer_param: description: - short: Output Protocol Configuration for ${label} - long: | - Select which Output Protocol to use for outputs ${label}. + short: Output Protocol Configuration for ${label} + long: | + Select which Output Protocol to use for outputs ${label}. - Custom PWM rates can be used by directly setting any value >0. + Custom PWM rates can be used by directly setting any value >0. type: enum default: 400 values: - -1: OneShot - 50: PWM 50 Hz - 100: PWM 100 Hz - 200: PWM 200 Hz - 400: PWM 400 Hz + -1: OneShot + 50: PWM 50 Hz + 100: PWM 100 Hz + 200: PWM 200 Hz + 400: PWM 400 Hz reboot_required: true +parameters: + - definitions: + PWM_SBUS_MODE: + default: 0 + description: + long: Set to 1 to enable S.BUS version 1 output instead of RSSI. + short: S.BUS out + type: boolean + volatile: false + group: PWM Outputs + - definitions: + SYS_USE_IO: + default: 1 + description: + long: Can be used to use a configure the use of the IO board. + short: Set usage of IO board + reboot_required: true + type: enum + values: + 0: IO PWM disabled (RC only) + 1: IO enabled (RC & PWM) + volatile: false + group: System diff --git a/src/drivers/px4io/px4io_params.c b/src/drivers/px4io/px4io_params.c deleted file mode 100644 index 84385e4216d8..000000000000 --- a/src/drivers/px4io/px4io_params.c +++ /dev/null @@ -1,65 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015-2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file px4io_params.c - * - * Parameters defined by the PX4IO driver - * - * @author Lorenz Meier - */ - -#include -#include - -/** - * Set usage of IO board - * - * Can be used to use a configure the use of the IO board. - * - * @value 0 IO PWM disabled (RC only) - * @value 1 IO enabled (RC & PWM) - * @reboot_required true - * @group System - */ -PARAM_DEFINE_INT32(SYS_USE_IO, 1); - -/** - * S.BUS out - * - * Set to 1 to enable S.BUS version 1 output instead of RSSI. - * - * @boolean - * @group PWM Outputs - */ -PARAM_DEFINE_INT32(PWM_SBUS_MODE, 0); diff --git a/src/drivers/rc_input/module.yaml b/src/drivers/rc_input/module.yaml index d0f9040a6ff8..a9cec91fb5f4 100644 --- a/src/drivers/rc_input/module.yaml +++ b/src/drivers/rc_input/module.yaml @@ -1,35 +1,33 @@ module_name: RC Input Driver parameters: - - group: RC Input - definitions: - RC_INPUT_PROTO: - description: - short: RC input protocol - long: | - Select your RC input protocol or auto to scan. - category: System - type: enum - values: - -1: Auto - 0: None - 1: PPM - 2: SBUS - 3: DSM - 4: ST24 - 5: SUMD - 6: CRSF - 7: GHST - min: -1 - max: 7 - default: -1 - + - group: RC Input + definitions: + RC_INPUT_PROTO: + description: + short: RC input protocol + long: | + Select your RC input protocol or auto to scan. + category: System + type: enum + values: + -1: Auto + 0: None + 1: PPM + 2: SBUS + 3: DSM + 4: ST24 + 5: SUMD + 6: CRSF + 7: GHST + min: -1 + max: 7 + default: -1 serial_config: - - command: set RC_INPUT_ARGS "-d ${SERIAL_DEV}" - port_config_param: - name: RC_PORT_CONFIG - group: Serial - default: RC - description_extended: | - Setting this to 'Disabled' will use a board-specific default port - for RC input. - + - command: set RC_INPUT_ARGS "-d ${SERIAL_DEV}" + port_config_param: + name: RC_PORT_CONFIG + group: Serial + default: RC + description_extended: | + Setting this to 'Disabled' will use a board-specific default port + for RC input. diff --git a/src/drivers/roboclaw/module.yaml b/src/drivers/roboclaw/module.yaml index 81e5f694dfee..ebbeff31f489 100644 --- a/src/drivers/roboclaw/module.yaml +++ b/src/drivers/roboclaw/module.yaml @@ -3,4 +3,72 @@ serial_config: - command: roboclaw start ${SERIAL_DEV} ${BAUD_PARAM} port_config_param: name: RBCLW_SER_CFG - group: Roboclaw \ No newline at end of file + group: Roboclaw +parameters: + - definitions: + RBCLW_ADDRESS: + default: 128 + description: + long: The Roboclaw can be configured to have an address from 0x80 to 0x87, inclusive. It must be configured to match this parameter. + short: Address of the Roboclaw + max: 135 + min: 128 + type: enum + values: + 128: '0x80' + 129: '0x81' + 130: '0x82' + 131: '0x83' + 132: '0x84' + 133: '0x85' + 134: '0x86' + 135: '0x87' + volatile: false + RBCLW_BAUD: + default: 2400 + description: + long: Baud rate of the serial communication with the Roboclaw. The Roboclaw must be configured to match this rate. + short: Roboclaw serial baud rate + max: 460800 + min: 2400 + reboot_required: true + type: enum + values: + 2400: 2400 baud + 9600: 9600 baud + 19200: 19200 baud + 38400: 38400 baud + 57600: 57600 baud + 115200: 115200 baud + 230400: 230400 baud + 460800: 460800 baud + volatile: false + RBCLW_COUNTS_REV: + default: 1200 + description: + long: Number of encoder counts for one revolution. The roboclaw treats analog encoders (potentiometers) as having 2047 counts per rev. The default value of 1200 corresponds to the default configuration of the Aion R1 rover. + short: Encoder counts per revolution + min: 1 + type: int32 + volatile: false + RBCLW_READ_PER: + default: 10 + description: + long: How long to wait, in Milliseconds, between reading wheel encoder values over Uart from the Roboclaw + short: Encoder read period + max: 1000 + min: 1 + type: int32 + unit: ms + volatile: false + RBCLW_WRITE_PER: + default: 10 + description: + long: How long to wait, in Milliseconds, between writing actuator controls over Uart to the Roboclaw + short: Uart write period + max: 1000 + min: 1 + type: int32 + unit: ms + volatile: false + group: Roboclaw driver diff --git a/src/drivers/roboclaw/roboclaw_params.c b/src/drivers/roboclaw/roboclaw_params.c deleted file mode 100644 index 3f3c938c55c0..000000000000 --- a/src/drivers/roboclaw/roboclaw_params.c +++ /dev/null @@ -1,114 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file roboclaw_params.c - * - * Parameters defined by the Roboclaw driver. - * - * The Roboclaw will need to be configured to match these parameters. For information about configuring the - * Roboclaw, see http://downloads.ionmc.com/docs/roboclaw_user_manual.pdf - * - * @author Timothy Scott - */ - - -/** - * Uart write period - * - * How long to wait, in Milliseconds, between writing actuator controls over Uart to the Roboclaw - * @unit ms - * @min 1 - * @max 1000 - * @group Roboclaw driver - */ -PARAM_DEFINE_INT32(RBCLW_WRITE_PER, 10); - -/** - * Encoder read period - * - * How long to wait, in Milliseconds, between reading wheel encoder values over Uart from the Roboclaw - * @unit ms - * @min 1 - * @max 1000 - * @group Roboclaw driver - */ -PARAM_DEFINE_INT32(RBCLW_READ_PER, 10); - -/** - * Encoder counts per revolution - * - * Number of encoder counts for one revolution. The roboclaw treats analog encoders (potentiometers) as having 2047 - * counts per rev. The default value of 1200 corresponds to the default configuration of the Aion R1 rover. - * @min 1 - * @group Roboclaw driver - */ -PARAM_DEFINE_INT32(RBCLW_COUNTS_REV, 1200); - -/** - * Address of the Roboclaw - * - * The Roboclaw can be configured to have an address from 0x80 to 0x87, inclusive. It must be configured to match - * this parameter. - * @min 128 - * @max 135 - * @value 128 0x80 - * @value 129 0x81 - * @value 130 0x82 - * @value 131 0x83 - * @value 132 0x84 - * @value 133 0x85 - * @value 134 0x86 - * @value 135 0x87 - * @group Roboclaw driver - */ -PARAM_DEFINE_INT32(RBCLW_ADDRESS, 128); - -/** - * Roboclaw serial baud rate - * - * Baud rate of the serial communication with the Roboclaw. The Roboclaw must be configured to match this rate. - * @min 2400 - * @max 460800 - * @value 2400 2400 baud - * @value 9600 9600 baud - * @value 19200 19200 baud - * @value 38400 38400 baud - * @value 57600 57600 baud - * @value 115200 115200 baud - * @value 230400 230400 baud - * @value 460800 460800 baud - * @group Roboclaw driver - * @reboot_required true - */ -PARAM_DEFINE_INT32(RBCLW_BAUD, 2400); diff --git a/src/drivers/rpm/pcf8583/CMakeLists.txt b/src/drivers/rpm/pcf8583/CMakeLists.txt index 9eef9031a77a..11150dfb4962 100644 --- a/src/drivers/rpm/pcf8583/CMakeLists.txt +++ b/src/drivers/rpm/pcf8583/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( PCF8583.cpp PCF8583.hpp pcf8583_main.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers__device px4_work_queue diff --git a/src/drivers/rpm/pcf8583/module.yaml b/src/drivers/rpm/pcf8583/module.yaml new file mode 100644 index 000000000000..03a8ef2ecd95 --- /dev/null +++ b/src/drivers/rpm/pcf8583/module.yaml @@ -0,0 +1,43 @@ +module_name: pcf8583 +parameters: + - definitions: + PCF8583_MAGNET: + default: 2 + description: + long: Nmumber of signals per rotation of actuator + short: PCF8583 rotorfreq (i2c) pulse count + min: 1 + reboot_required: true + type: int32 + volatile: false + PCF8583_POOL: + default: 1000000 + description: + long: Determines how often the sensor is read out. + short: PCF8583 rotorfreq (i2c) pool interval + reboot_required: true + type: int32 + unit: us + volatile: false + PCF8583_RESET: + default: 500000 + description: + long: Internal device counter is reset to 0 when overun this value, counter is able to store upto 6 digits reset of counter takes some time - measurement with reset has worse accurancy. 0 means reset counter after every measurement. + short: PCF8583 rotorfreq (i2c) pulse reset value + reboot_required: true + type: int32 + volatile: false + SENS_EN_PCF8583: + default: 0 + description: + long: Run PCF8583 driver automatically + short: PCF8583 eneable driver + max: 1 + min: 0 + reboot_required: true + type: enum + values: + 0: Disabled + 1: Eneabled + volatile: false + group: Sensors diff --git a/src/drivers/rpm/pcf8583/parameters.c b/src/drivers/rpm/pcf8583/parameters.c deleted file mode 100644 index bf2d41b6fdde..000000000000 --- a/src/drivers/rpm/pcf8583/parameters.c +++ /dev/null @@ -1,82 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* PCF8583 eneable driver -* -* Run PCF8583 driver automatically -* -* @reboot_required true -* @min 0 -* @max 1 -* @group Sensors -* @value 0 Disabled -* @value 1 Eneabled -*/ -PARAM_DEFINE_INT32(SENS_EN_PCF8583, 0); - - -/** - * PCF8583 rotorfreq (i2c) pool interval - * - * Determines how often the sensor is read out. - * - * @reboot_required true - * @group Sensors - * @unit us - */ -PARAM_DEFINE_INT32(PCF8583_POOL, 1000000); - -/** - * PCF8583 rotorfreq (i2c) pulse reset value - * - * Internal device counter is reset to 0 when overun this value, - * counter is able to store upto 6 digits - * reset of counter takes some time - measurement with reset has worse accurancy. - * 0 means reset counter after every measurement. - * - * @reboot_required true - * @group Sensors - */ -PARAM_DEFINE_INT32(PCF8583_RESET, 500000); - -/** - * PCF8583 rotorfreq (i2c) pulse count - * - * Nmumber of signals per rotation of actuator - * - * @reboot_required true - * @group Sensors - * @min 1 - */ -PARAM_DEFINE_INT32(PCF8583_MAGNET, 2); diff --git a/src/drivers/smart_battery/batmon/CMakeLists.txt b/src/drivers/smart_battery/batmon/CMakeLists.txt index 8025d6a034ac..f156ece59cc2 100644 --- a/src/drivers/smart_battery/batmon/CMakeLists.txt +++ b/src/drivers/smart_battery/batmon/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS batmon.cpp + MODULE_CONFIG + module.yaml DEPENDS drivers__smbus_sbs drivers__smbus diff --git a/src/drivers/smart_battery/batmon/batmon_params.c b/src/drivers/smart_battery/batmon/batmon_params.c deleted file mode 100644 index 66a2bd28fceb..000000000000 --- a/src/drivers/smart_battery/batmon/batmon_params.c +++ /dev/null @@ -1,61 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file batmon_params.c - * Smart battery driver parameters for BatMon (rotoye.com/batmon) - * - * @author Eohan George - */ - -/** - * Parameter to enable BatMon module - * - * @reboot_required true - * @min 0 - * @max 2 - * @group Sensors - * @value 0 Disabled - * @value 1 Start on default I2C addr(BATMON_ADDR_DFLT) - * @value 2 Autodetect I2C address (TODO) - */ -PARAM_DEFINE_INT32(BATMON_DRIVER_EN, 0); - -/** - * I2C address for BatMon battery 1 - * - * @reboot_required true - * @decimal 1 - * @group Sensors - */ -PARAM_DEFINE_INT32(BATMON_ADDR_DFLT, 11); //0x0B diff --git a/src/drivers/smart_battery/batmon/module.yaml b/src/drivers/smart_battery/batmon/module.yaml new file mode 100644 index 000000000000..b3022e386bc4 --- /dev/null +++ b/src/drivers/smart_battery/batmon/module.yaml @@ -0,0 +1,25 @@ +module_name: batmon +parameters: + - definitions: + BATMON_ADDR_DFLT: + decimal: 1 + default: 11 + description: + short: I2C address for BatMon battery 1 + reboot_required: true + type: int32 + volatile: false + BATMON_DRIVER_EN: + default: 0 + description: + short: Parameter to enable BatMon module + max: 2 + min: 0 + reboot_required: true + type: enum + values: + 0: Disabled + 1: Start on default I2C addr(BATMON_ADDR_DFLT) + 2: Autodetect I2C address (TODO) + volatile: false + group: Sensors diff --git a/src/drivers/tap_esc/module.yaml b/src/drivers/tap_esc/module.yaml index 29d9845eb300..c3db0bec2a3b 100644 --- a/src/drivers/tap_esc/module.yaml +++ b/src/drivers/tap_esc/module.yaml @@ -1,6 +1,33 @@ -module_name: TAP ESC Output +module_name: tap_esc actuator_output: output_groups: - param_prefix: TAP_ESC channel_label: 'ESC' num_channels: 8 +parameters: + - definitions: + ESC_BL_VER: + default: 0 + description: + short: Required esc bootloader version + max: 65535 + min: 0 + type: int32 + volatile: false + ESC_FW_VER: + default: 0 + description: + short: Required esc firmware version + max: 65535 + min: 0 + type: int32 + volatile: false + ESC_HW_VER: + default: 0 + description: + short: Required esc hardware version + max: 65535 + min: 0 + type: int32 + volatile: false + group: ESC diff --git a/src/drivers/tap_esc/tap_esc_params.c b/src/drivers/tap_esc/tap_esc_params.c deleted file mode 100644 index fae32a918ed5..000000000000 --- a/src/drivers/tap_esc/tap_esc_params.c +++ /dev/null @@ -1,32 +0,0 @@ -/** - * @file tap_esc_params.c - * Parameters for esc version - * - */ - -/** - * Required esc firmware version. - * - * @group ESC - * @min 0 - * @max 65535 - */ -PARAM_DEFINE_INT32(ESC_FW_VER, 0); - -/** - * Required esc bootloader version. - * - * @group ESC - * @min 0 - * @max 65535 - */ -PARAM_DEFINE_INT32(ESC_BL_VER, 0); - -/** - * Required esc hardware version - * - * @group ESC - * @min 0 - * @max 65535 - */ -PARAM_DEFINE_INT32(ESC_HW_VER, 0); diff --git a/src/drivers/telemetry/bst/CMakeLists.txt b/src/drivers/telemetry/bst/CMakeLists.txt index c9c9e7ff798e..2160d0304827 100644 --- a/src/drivers/telemetry/bst/CMakeLists.txt +++ b/src/drivers/telemetry/bst/CMakeLists.txt @@ -36,6 +36,8 @@ px4_add_module( COMPILE_FLAGS SRCS bst.cpp + MODULE_CONFIG + module.yaml DEPENDS ) diff --git a/src/drivers/telemetry/bst/bst_params.c b/src/drivers/telemetry/bst/bst_params.c deleted file mode 100644 index 5e6452ab1091..000000000000 --- a/src/drivers/telemetry/bst/bst_params.c +++ /dev/null @@ -1,43 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Blacksheep telemetry Enable - * - * If true, the FMU will try to connect to Blacksheep telemetry on start up - * - * @boolean - * @reboot_required true - * @group Telemetry - */ -PARAM_DEFINE_INT32(TEL_BST_EN, 0); diff --git a/src/drivers/telemetry/bst/module.yaml b/src/drivers/telemetry/bst/module.yaml new file mode 100644 index 000000000000..1d85da11819f --- /dev/null +++ b/src/drivers/telemetry/bst/module.yaml @@ -0,0 +1,12 @@ +module_name: bst +parameters: + - definitions: + TEL_BST_EN: + default: 0 + description: + long: If true, the FMU will try to connect to Blacksheep telemetry on start up + short: Blacksheep telemetry Enable + reboot_required: true + type: boolean + volatile: false + group: Telemetry diff --git a/src/drivers/telemetry/frsky_telemetry/module.yaml b/src/drivers/telemetry/frsky_telemetry/module.yaml index 796342de9c66..7a210ca85479 100644 --- a/src/drivers/telemetry/frsky_telemetry/module.yaml +++ b/src/drivers/telemetry/frsky_telemetry/module.yaml @@ -1,7 +1,6 @@ module_name: FrSky Telemetry serial_config: - - command: frsky_telemetry start -d ${SERIAL_DEV} - port_config_param: - name: TEL_FRSKY_CONFIG - group: Telemetry - + - command: frsky_telemetry start -d ${SERIAL_DEV} + port_config_param: + name: TEL_FRSKY_CONFIG + group: Telemetry diff --git a/src/drivers/telemetry/hott/hott_telemetry/module.yaml b/src/drivers/telemetry/hott/hott_telemetry/module.yaml index ff50a8e3d4ee..c49dd5f7b4ac 100644 --- a/src/drivers/telemetry/hott/hott_telemetry/module.yaml +++ b/src/drivers/telemetry/hott/hott_telemetry/module.yaml @@ -1,7 +1,6 @@ module_name: HoTT Telemetry serial_config: - - command: hott_telemetry start -d ${SERIAL_DEV} - port_config_param: - name: TEL_HOTT_CONFIG - group: Telemetry - + - command: hott_telemetry start -d ${SERIAL_DEV} + port_config_param: + name: TEL_HOTT_CONFIG + group: Telemetry diff --git a/src/drivers/telemetry/iridiumsbd/iridiumsbd_params.c b/src/drivers/telemetry/iridiumsbd/iridiumsbd_params.c deleted file mode 100644 index 4f198b000194..000000000000 --- a/src/drivers/telemetry/iridiumsbd/iridiumsbd_params.c +++ /dev/null @@ -1,32 +0,0 @@ - -/** - * Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call. - * - * @unit s - * @min 0 - * @max 5000 - * @group Iridium SBD - */ -PARAM_DEFINE_INT32(ISBD_READ_INT, 0); - -/** - * Iridium SBD session timeout - * - * @unit s - * @min 0 - * @max 300 - * @group Iridium SBD - */ -PARAM_DEFINE_INT32(ISBD_SBD_TIMEOUT, 60); - -/** - * Time the Iridium driver will wait for additional mavlink messages to combine them into one SBD message - * - * Value 0 turns the functionality off - * - * @unit ms - * @min 0 - * @max 500 - * @group Iridium SBD - */ -PARAM_DEFINE_INT32(ISBD_STACK_TIME, 0); diff --git a/src/drivers/telemetry/iridiumsbd/module.yaml b/src/drivers/telemetry/iridiumsbd/module.yaml index 5fa8d138c4c4..77d9b1311a0f 100644 --- a/src/drivers/telemetry/iridiumsbd/module.yaml +++ b/src/drivers/telemetry/iridiumsbd/module.yaml @@ -1,15 +1,45 @@ -module_name: Iridium (with MAVLink) +module_name: iridiumsbd serial_config: - - command: | - # add a sleep here to make sure that the module is powered - usleep 200000 - if iridiumsbd start -d ${SERIAL_DEV} - then - mavlink start -d /dev/iridium -m iridium -b 115200 - else - tune_control play error - fi - port_config_param: - name: ISBD_CONFIG - group: Iridium SBD - + - command: | + # add a sleep here to make sure that the module is powered + usleep 200000 + if iridiumsbd start -d ${SERIAL_DEV} + then + mavlink start -d /dev/iridium -m iridium -b 115200 + else + tune_control play error + fi + port_config_param: + name: ISBD_CONFIG + group: Iridium SBD +parameters: + - definitions: + ISBD_READ_INT: + default: 0 + description: + short: Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call + max: 5000 + min: 0 + type: int32 + unit: s + volatile: false + ISBD_SBD_TIMEOUT: + default: 60 + description: + short: Iridium SBD session timeout + max: 300 + min: 0 + type: int32 + unit: s + volatile: false + ISBD_STACK_TIME: + default: 0 + description: + long: Value 0 turns the functionality off + short: Time the Iridium driver will wait for additional mavlink messages to combine them into one SBD message + max: 500 + min: 0 + type: int32 + unit: ms + volatile: false + group: Iridium SBD diff --git a/src/drivers/transponder/sagetech_mxs/module.yaml b/src/drivers/transponder/sagetech_mxs/module.yaml index d5d8b30d194a..d3014673bd9f 100644 --- a/src/drivers/transponder/sagetech_mxs/module.yaml +++ b/src/drivers/transponder/sagetech_mxs/module.yaml @@ -1,7 +1,213 @@ -module_name: Sagetech MXS +module_name: sagetech_mxs serial_config: - - command: sagetech_mxs start -d ${SERIAL_DEV} - port_config_param: - name: MXS_SER_CFG - group: Transponder - label: Sagetech MXS Serial Port + - command: sagetech_mxs start -d ${SERIAL_DEV} + port_config_param: + name: MXS_SER_CFG + group: Transponder + label: Sagetech MXS Serial Port +parameters: + - definitions: + SER_MXS_BAUD: + default: 5 + description: + long: Baudrate for the Serial Port connected to the MXS Transponder + short: MXS Serial Communication Baud rate + max: 10 + min: 0 + reboot_required: true + type: enum + values: + 0: '38400' + 1: '600' + 2: '4800' + 3: '9600' + 4: RESERVED + 5: '57600' + 6: '115200' + 7: '230400' + 8: '19200' + 9: '460800' + 10: '921600' + volatile: false + group: Serial + - definitions: + ADSB_EMERGC: + default: 0 + description: + long: Sets the vehicle emergency state + short: ADSB-Out Emergency State + max: 6 + min: 0 + reboot_required: false + type: enum + values: + 0: NoEmergency + 1: General + 2: Medical + 3: LowFuel + 4: NoCommunications + 5: Interference + 6: Downed + volatile: false + ADSB_EMIT_TYPE: + default: 14 + description: + long: Configure the emitter type of the vehicle. + short: ADSB-Out Vehicle Emitter Type + max: 15 + min: 0 + reboot_required: true + type: enum + values: + 0: Unknown + 1: Light + 2: Small + 3: Large + 4: HighVortex + 5: Heavy + 6: Performance + 7: Rotorcraft + 8: RESERVED + 9: Glider + 10: LightAir + 11: Parachute + 12: UltraLight + 13: RESERVED + 14: UAV + 15: Space + 16: RESERVED + 17: EmergencySurf + 18: ServiceSurf + 19: PointObstacle + volatile: false + ADSB_ICAO_ID: + default: 1194684 + description: + long: Defines the ICAO ID of the vehicle + short: ADSB-Out ICAO configuration + max: 16777215 + min: -1 + reboot_required: true + type: int32 + volatile: false + ADSB_ICAO_SPECL: + default: 0 + description: + long: This vehicle is always tracked. Use 0 to disable. + short: ADSB-In Special ICAO configuration + max: 16777215 + min: 0 + reboot_required: false + type: int32 + volatile: false + ADSB_IDENT: + default: 0 + description: + long: Enable Identification of Position feature + short: ADSB-Out Ident Configuration + reboot_required: false + type: boolean + volatile: false + ADSB_LEN_WIDTH: + default: 1 + description: + long: Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size. + short: ADSB-Out Vehicle Size Configuration + max: 15 + min: 0 + reboot_required: true + type: enum + values: + 0: SizeUnknown + 1: Len15_Wid23 + 2: Len25_Wid28 + 3: Len25_Wid34 + 4: Len35_Wid33 + 5: Len35_Wid38 + 6: Len45_Wid39 + 7: Len45_Wid45 + 8: Len55_Wid45 + 9: Len55_Wid52 + 10: Len65_Wid59 + 11: Len65_Wid67 + 12: Len75_Wid72 + 13: Len75_Wid80 + 14: Len85_Wid80 + 15: Len85_Wid90 + volatile: false + ADSB_LIST_MAX: + default: 25 + description: + long: Change number of targets to track + short: ADSB-In Vehicle List Size + max: 50 + min: 0 + reboot_required: true + type: int32 + volatile: false + ADSB_MAX_SPEED: + default: 0 + description: + long: Informs ADSB vehicles of this vehicle's max speed capability + short: ADSB-Out Vehicle Max Speed + max: 6 + min: 0 + reboot_required: true + type: enum + values: + 0: UnknownMaxSpeed + 1: 75Kts + 2: 150Kts + 3: 300Kts + 4: 600Kts + 5: 1200Kts + 6: Over1200Kts + volatile: false + ADSB_SQUAWK: + default: 1200 + description: + long: This parameter defines the squawk code. Value should be between 0000 and 7777. + short: ADSB-Out squawk code configuration + max: 7777 + min: 0 + reboot_required: false + type: int32 + volatile: false + MXS_EXT_CFG: + default: 0 + description: + long: Disables auto-configuration mode enabling MXS config through external software. + short: Sagetech External Configuration Mode + reboot_required: true + type: boolean + volatile: false + MXS_OP_MODE: + default: 0 + description: + long: This parameter defines the operating mode of the MXS + short: Sagetech MXS mode configuration + max: 3 + min: 0 + reboot_required: false + type: enum + values: + 0: 'Off' + 1: 'On' + 2: Standby + 3: Alt + volatile: false + MXS_TARG_PORT: + default: 1 + description: + long: The MXS communication port to receive Target data from + short: Sagetech MXS Participant Configuration + max: 2 + min: 0 + reboot_required: false + type: enum + values: + 0: Auto + 1: COM0 + 2: COM1 + volatile: false + group: Transponder diff --git a/src/drivers/transponder/sagetech_mxs/parameters.c b/src/drivers/transponder/sagetech_mxs/parameters.c deleted file mode 100644 index 0d31d1a44544..000000000000 --- a/src/drivers/transponder/sagetech_mxs/parameters.c +++ /dev/null @@ -1,269 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* - * parameters.c - * - * Sagetech MXS transponder custom parameters - * @author Megan McCormick megan.mccormick@sagetech.com - * @author Check Faber chuck.faber@sagetech.com - */ - -/** - * ADSB-Out squawk code configuration - * - * This parameter defines the squawk code. Value should be between 0000 and 7777. - * - * @reboot_required false - * @min 0 - * @max 7777 - * @group Transponder - * - */ -PARAM_DEFINE_INT32(ADSB_SQUAWK, 1200); - -/** - * ADSB-Out Ident Configuration - * - * Enable Identification of Position feature - * - * @boolean - * @reboot_required false - * @group Transponder - */ -PARAM_DEFINE_INT32(ADSB_IDENT, 0); - -/** - * ADSB-In Vehicle List Size - * - * Change number of targets to track - * - * @min 0 - * @max 50 - * @reboot_required true - * @group Transponder - */ -PARAM_DEFINE_INT32(ADSB_LIST_MAX, 25); - -/** - * ADSB-Out ICAO configuration - * - * Defines the ICAO ID of the vehicle - * - * @reboot_required true - * @min -1 - * @max 16777215 - * @group Transponder - * - */ -PARAM_DEFINE_INT32(ADSB_ICAO_ID, 1194684); - -/** - * ADSB-Out Vehicle Size Configuration - * - * Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size. - * - * @reboot_required true - * @min 0 - * @max 15 - * @group Transponder - * - * @value 0 SizeUnknown - * @value 1 Len15_Wid23 - * @value 2 Len25_Wid28 - * @value 3 Len25_Wid34 - * @value 4 Len35_Wid33 - * @value 5 Len35_Wid38 - * @value 6 Len45_Wid39 - * @value 7 Len45_Wid45 - * @value 8 Len55_Wid45 - * @value 9 Len55_Wid52 - * @value 10 Len65_Wid59 - * @value 11 Len65_Wid67 - * @value 12 Len75_Wid72 - * @value 13 Len75_Wid80 - * @value 14 Len85_Wid80 - * @value 15 Len85_Wid90 - */ -PARAM_DEFINE_INT32(ADSB_LEN_WIDTH, 1); - -/** - * ADSB-Out Vehicle Emitter Type - * - * Configure the emitter type of the vehicle. - * - * @reboot_required true - * @min 0 - * @max 15 - * @group Transponder - * - * @value 0 Unknown - * @value 1 Light - * @value 2 Small - * @value 3 Large - * @value 4 HighVortex - * @value 5 Heavy - * @value 6 Performance - * @value 7 Rotorcraft - * @value 8 RESERVED - * @value 9 Glider - * @value 10 LightAir - * @value 11 Parachute - * @value 12 UltraLight - * @value 13 RESERVED - * @value 14 UAV - * @value 15 Space - * @value 16 RESERVED - * @value 17 EmergencySurf - * @value 18 ServiceSurf - * @value 19 PointObstacle - */ -PARAM_DEFINE_INT32(ADSB_EMIT_TYPE, 14); - -/** - * ADSB-Out Vehicle Max Speed - * - * Informs ADSB vehicles of this vehicle's max speed capability - * - * @reboot_required true - * @min 0 - * @max 6 - * @value 0 UnknownMaxSpeed - * @value 1 75Kts - * @value 2 150Kts - * @value 3 300Kts - * @value 4 600Kts - * @value 5 1200Kts - * @value 6 Over1200Kts - * @group Transponder - */ -PARAM_DEFINE_INT32(ADSB_MAX_SPEED, 0); - -/** - * ADSB-In Special ICAO configuration - * - * This vehicle is always tracked. Use 0 to disable. - * - * @reboot_required false - * @min 0 - * @max 16777215 - * @group Transponder - * - */ -PARAM_DEFINE_INT32(ADSB_ICAO_SPECL, 0); - -/** - * ADSB-Out Emergency State - * - * Sets the vehicle emergency state - * - * @reboot_required false - * @min 0 - * @max 6 - * @value 0 NoEmergency - * @value 1 General - * @value 2 Medical - * @value 3 LowFuel - * @value 4 NoCommunications - * @value 5 Interference - * @value 6 Downed - * @group Transponder - */ -PARAM_DEFINE_INT32(ADSB_EMERGC, 0); - -/** - * Sagetech MXS mode configuration - * - * This parameter defines the operating mode of the MXS - * - * @reboot_required false - * @min 0 - * @max 3 - * @group Transponder - * - * @value 0 Off - * @value 1 On - * @value 2 Standby - * @value 3 Alt - */ -PARAM_DEFINE_INT32(MXS_OP_MODE, 0); - -/** - * Sagetech MXS Participant Configuration - * - * The MXS communication port to receive Target data from - * - * @min 0 - * @max 2 - * @reboot_required false - * @group Transponder - * - * @value 0 Auto - * @value 1 COM0 - * @value 2 COM1 - */ -PARAM_DEFINE_INT32(MXS_TARG_PORT, 1); - -/** - * Sagetech External Configuration Mode - * - * Disables auto-configuration mode enabling MXS config through external software. - * - * @reboot_required true - * @boolean - * @group Transponder - */ -PARAM_DEFINE_INT32(MXS_EXT_CFG, 0); - -/** - * MXS Serial Communication Baud rate - * - * Baudrate for the Serial Port connected to the MXS Transponder - * - * @reboot_required true - * @min 0 - * @max 10 - * @value 0 38400 - * @value 1 600 - * @value 2 4800 - * @value 3 9600 - * @value 4 RESERVED - * @value 5 57600 - * @value 6 115200 - * @value 7 230400 - * @value 8 19200 - * @value 9 460800 - * @value 10 921600 - * @group Serial - */ -PARAM_DEFINE_INT32(SER_MXS_BAUD, 5); diff --git a/src/drivers/uavcan/module.yaml b/src/drivers/uavcan/module.yaml index 9c2ba643dce8..49f3b63ca9f9 100644 --- a/src/drivers/uavcan/module.yaml +++ b/src/drivers/uavcan/module.yaml @@ -12,16 +12,255 @@ actuator_output: group_label: 'ESCs' channel_label: 'ESC' standard_params: - min: { min: 0, max: 8191, default: 1 } - max: { min: 0, max: 8191, default: 8191 } - failsafe: { min: 0, max: 8191 } + min: {min: 0, max: 8191, default: 1} + max: {min: 0, max: 8191, default: 8191} + failsafe: {min: 0, max: 8191} num_channels: 8 - param_prefix: UAVCAN_SV group_label: 'Servos' channel_label: 'Servo' standard_params: - disarmed: { min: 0, max: 1000, default: 500 } - min: { min: 0, max: 1000, default: 0 } - max: { min: 0, max: 1000, default: 1000 } - failsafe: { min: 0, max: 1000 } + disarmed: {min: 0, max: 1000, default: 500} + min: {min: 0, max: 1000, default: 0} + max: {min: 0, max: 1000, default: 1000} + failsafe: {min: 0, max: 1000} num_channels: 8 +parameters: + - definitions: + UAVCAN_BITRATE: + default: 1000000 + description: + short: UAVCAN CAN bus bitrate + max: 1000000 + min: 20000 + reboot_required: true + type: int32 + unit: bit/s + volatile: false + UAVCAN_ENABLE: + default: 0 + description: + long: 0 - UAVCAN disabled. 1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update. 2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update. 3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN. + short: UAVCAN mode + max: 3 + min: 0 + reboot_required: true + type: enum + values: + 0: Disabled + 1: Sensors Manual Config + 2: Sensors Automatic Config + 3: Sensors and Actuators (ESCs) Automatic Config + volatile: false + UAVCAN_ESC_IDLT: + default: 1 + description: + short: UAVCAN ESC will spin at idle throttle when armed, even if the mixer outputs zero setpoints + reboot_required: true + type: boolean + volatile: false + UAVCAN_LGT_ANTCL: + default: 2 + description: + long: This parameter defines the minimum condition under which the system will command the ANTI_COLLISION lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on + short: UAVCAN ANTI_COLLISION light operating mode + max: 3 + min: 0 + reboot_required: true + type: enum + values: + 0: Always off + 1: When autopilot is armed + 2: When autopilot is prearmed + 3: Always on + volatile: false + UAVCAN_LGT_LAND: + default: 0 + description: + long: This parameter defines the minimum condition under which the system will command the LIGHT_ID_LANDING lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on + short: UAVCAN LIGHT_ID_LANDING light operating mode + max: 3 + min: 0 + reboot_required: true + type: enum + values: + 0: Always off + 1: When autopilot is armed + 2: When autopilot is prearmed + 3: Always on + volatile: false + UAVCAN_LGT_NAV: + default: 3 + description: + long: This parameter defines the minimum condition under which the system will command the RIGHT_OF_WAY lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on + short: UAVCAN RIGHT_OF_WAY light operating mode + max: 3 + min: 0 + reboot_required: true + type: enum + values: + 0: Always off + 1: When autopilot is armed + 2: When autopilot is prearmed + 3: Always on + volatile: false + UAVCAN_LGT_STROB: + default: 1 + description: + long: This parameter defines the minimum condition under which the system will command the STROBE lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on + short: UAVCAN STROBE light operating mode + max: 3 + min: 0 + reboot_required: true + type: enum + values: + 0: Always off + 1: When autopilot is armed + 2: When autopilot is prearmed + 3: Always on + volatile: false + UAVCAN_NODE_ID: + default: 1 + description: + long: Read the specs at http://uavcan.org to learn more about Node ID. + short: UAVCAN Node ID + max: 125 + min: 1 + reboot_required: true + type: int32 + volatile: false + UAVCAN_PUB_MBD: + default: 0 + description: + long: Enable UAVCAN RTCM stream publication ardupilot::gnss::MovingBaselineData + short: publish moving baseline data RTCM stream + reboot_required: true + type: boolean + volatile: false + UAVCAN_PUB_RTCM: + default: 0 + description: + long: Enable UAVCAN RTCM stream publication uavcan::equipment::gnss::RTCMStream + short: publish RTCM stream + reboot_required: true + type: boolean + volatile: false + UAVCAN_RNG_MAX: + default: 200.0 + description: + long: This parameter defines the maximum valid range for a rangefinder connected via UAVCAN. + short: UAVCAN rangefinder maximum range + type: float + unit: m + volatile: false + UAVCAN_RNG_MIN: + default: 0.3 + description: + long: This parameter defines the minimum valid range for a rangefinder connected via UAVCAN. + short: UAVCAN rangefinder minimum range + type: float + unit: m + volatile: false + UAVCAN_SUB_ASPD: + default: 0 + description: + long: Enable UAVCAN airspeed subscriptions. uavcan::equipment::air_data::IndicatedAirspeed uavcan::equipment::air_data::TrueAirspeed uavcan::equipment::air_data::StaticTemperature + short: subscription airspeed + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_BARO: + default: 0 + description: + long: Enable UAVCAN barometer subscription. uavcan::equipment::air_data::StaticPressure uavcan::equipment::air_data::StaticTemperature + short: subscription barometer + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_BAT: + default: 0 + description: + long: Enable UAVCAN battery subscription. uavcan::equipment::power::BatteryInfo ardupilot::equipment::power::BatteryInfoAux 0 - Disable 1 - Use raw data. Recommended for Smart battery 2 - Filter the data with internal battery library + short: subscription battery + max: 2 + min: 0 + reboot_required: true + type: enum + values: + 0: Disable + 1: Raw data + 2: Filter data + volatile: false + UAVCAN_SUB_BTN: + default: 0 + description: + long: Enable UAVCAN button subscription. ardupilot::indication::Button + short: subscription button + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_DPRES: + default: 0 + description: + long: Enable UAVCAN differential pressure subscription. uavcan::equipment::air_data::RawAirData + short: subscription differential pressure + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_FLOW: + default: 0 + description: + long: Enable UAVCAN optical flow subscription. + short: subscription flow + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_GPS: + default: 1 + description: + long: Enable UAVCAN GPS subscriptions. uavcan::equipment::gnss::Fix uavcan::equipment::gnss::Fix2 uavcan::equipment::gnss::Auxiliary + short: subscription GPS + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_HYGRO: + default: 0 + description: + long: Enable UAVCAN hygrometer subscriptions. dronecan::sensors::hygrometer::Hygrometer + short: subscription hygrometer + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_ICE: + default: 0 + description: + long: Enable UAVCAN internal combusion engine (ICE) subscription. uavcan::equipment::ice::reciprocating::Status + short: subscription ICE + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_IMU: + default: 0 + description: + long: Enable UAVCAN IMU subscription. uavcan::equipment::ahrs::RawIMU + short: subscription IMU + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_MAG: + default: 1 + description: + long: Enable UAVCAN mag subscription. uavcan::equipment::ahrs::MagneticFieldStrength uavcan::equipment::ahrs::MagneticFieldStrength2 + short: subscription magnetometer + reboot_required: true + type: boolean + volatile: false + UAVCAN_SUB_RNG: + default: 0 + description: + long: Enable UAVCAN range finder subscription. uavcan::equipment::range_sensor::Measurement + short: subscription range finder + reboot_required: true + type: boolean + volatile: false + group: UAVCAN diff --git a/src/drivers/uavcan/uavcan_params.c b/src/drivers/uavcan/uavcan_params.c deleted file mode 100644 index 0766f52ed1f4..000000000000 --- a/src/drivers/uavcan/uavcan_params.c +++ /dev/null @@ -1,377 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @author Pavel Kirienko - */ - -/** - * UAVCAN mode - * - * 0 - UAVCAN disabled. - * 1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update. - * 2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update. - * 3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN. - * - * @min 0 - * @max 3 - * @value 0 Disabled - * @value 1 Sensors Manual Config - * @value 2 Sensors Automatic Config - * @value 3 Sensors and Actuators (ESCs) Automatic Config - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_ENABLE, 0); - -/** - * UAVCAN Node ID. - * - * Read the specs at http://uavcan.org to learn more about Node ID. - * - * @min 1 - * @max 125 - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_NODE_ID, 1); - -/** - * UAVCAN CAN bus bitrate. - * - * @unit bit/s - * @min 20000 - * @max 1000000 - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_BITRATE, 1000000); - -/** - * UAVCAN ESC will spin at idle throttle when armed, even if the mixer outputs zero setpoints. - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_ESC_IDLT, 1); - -/** - * UAVCAN rangefinder minimum range - * - * This parameter defines the minimum valid range for a rangefinder connected via UAVCAN. - * - * @unit m - * @group UAVCAN - */ -PARAM_DEFINE_FLOAT(UAVCAN_RNG_MIN, 0.3f); - -/** - * UAVCAN rangefinder maximum range - * - * This parameter defines the maximum valid range for a rangefinder connected via UAVCAN. - * - * @unit m - * @group UAVCAN - */ -PARAM_DEFINE_FLOAT(UAVCAN_RNG_MAX, 200.0f); - -/** - * UAVCAN ANTI_COLLISION light operating mode - * - * This parameter defines the minimum condition under which the system will command - * the ANTI_COLLISION lights on - * - * 0 - Always off - * 1 - When autopilot is armed - * 2 - When autopilot is prearmed - * 3 - Always on - * - * @min 0 - * @max 3 - * @value 0 Always off - * @value 1 When autopilot is armed - * @value 2 When autopilot is prearmed - * @value 3 Always on - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_LGT_ANTCL, 2); - -/** - * UAVCAN STROBE light operating mode - * - * This parameter defines the minimum condition under which the system will command - * the STROBE lights on - * - * 0 - Always off - * 1 - When autopilot is armed - * 2 - When autopilot is prearmed - * 3 - Always on - * - * @min 0 - * @max 3 - * @value 0 Always off - * @value 1 When autopilot is armed - * @value 2 When autopilot is prearmed - * @value 3 Always on - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_LGT_STROB, 1); - -/** - * UAVCAN RIGHT_OF_WAY light operating mode - * - * This parameter defines the minimum condition under which the system will command - * the RIGHT_OF_WAY lights on - * - * 0 - Always off - * 1 - When autopilot is armed - * 2 - When autopilot is prearmed - * 3 - Always on - * - * @min 0 - * @max 3 - * @value 0 Always off - * @value 1 When autopilot is armed - * @value 2 When autopilot is prearmed - * @value 3 Always on - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_LGT_NAV, 3); - -/** - * UAVCAN LIGHT_ID_LANDING light operating mode - * - * This parameter defines the minimum condition under which the system will command - * the LIGHT_ID_LANDING lights on - * - * 0 - Always off - * 1 - When autopilot is armed - * 2 - When autopilot is prearmed - * 3 - Always on - * - * @min 0 - * @max 3 - * @value 0 Always off - * @value 1 When autopilot is armed - * @value 2 When autopilot is prearmed - * @value 3 Always on - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_LGT_LAND, 0); - -/** - * publish RTCM stream - * - * Enable UAVCAN RTCM stream publication - * uavcan::equipment::gnss::RTCMStream - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_PUB_RTCM, 0); - -/** - * publish moving baseline data RTCM stream - * - * Enable UAVCAN RTCM stream publication - * ardupilot::gnss::MovingBaselineData - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_PUB_MBD, 0); - -/** - * subscription airspeed - * - * Enable UAVCAN airspeed subscriptions. - * uavcan::equipment::air_data::IndicatedAirspeed - * uavcan::equipment::air_data::TrueAirspeed - * uavcan::equipment::air_data::StaticTemperature - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_ASPD, 0); - -/** - * subscription barometer - * - * Enable UAVCAN barometer subscription. - * uavcan::equipment::air_data::StaticPressure - * uavcan::equipment::air_data::StaticTemperature - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_BARO, 0); - -/** - * subscription battery - * - * Enable UAVCAN battery subscription. - * uavcan::equipment::power::BatteryInfo - * ardupilot::equipment::power::BatteryInfoAux - * - * 0 - Disable - * 1 - Use raw data. Recommended for Smart battery - * 2 - Filter the data with internal battery library - * - * @min 0 - * @max 2 - * @value 0 Disable - * @value 1 Raw data - * @value 2 Filter data - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_BAT, 0); - -/** - * subscription differential pressure - * - * Enable UAVCAN differential pressure subscription. - * uavcan::equipment::air_data::RawAirData - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_DPRES, 0); - -/** - * subscription flow - * - * Enable UAVCAN optical flow subscription. - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_FLOW, 0); - -/** - * subscription GPS - * - * Enable UAVCAN GPS subscriptions. - * uavcan::equipment::gnss::Fix - * uavcan::equipment::gnss::Fix2 - * uavcan::equipment::gnss::Auxiliary - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_GPS, 1); - -/** - * subscription hygrometer - * - * Enable UAVCAN hygrometer subscriptions. - * dronecan::sensors::hygrometer::Hygrometer - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_HYGRO, 0); - -/** - * subscription ICE - * - * Enable UAVCAN internal combusion engine (ICE) subscription. - * uavcan::equipment::ice::reciprocating::Status - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_ICE, 0); - -/** - * subscription IMU - * - * Enable UAVCAN IMU subscription. - * uavcan::equipment::ahrs::RawIMU - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_IMU, 0); - -/** - * subscription magnetometer - * - * Enable UAVCAN mag subscription. - * uavcan::equipment::ahrs::MagneticFieldStrength - * uavcan::equipment::ahrs::MagneticFieldStrength2 - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_MAG, 1); - -/** - * subscription range finder - * - * Enable UAVCAN range finder subscription. - * uavcan::equipment::range_sensor::Measurement - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_RNG, 0); - -/** - * subscription button - * - * Enable UAVCAN button subscription. - * ardupilot::indication::Button - * - * @boolean - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_SUB_BTN, 0); diff --git a/src/drivers/uavcannode/CMakeLists.txt b/src/drivers/uavcannode/CMakeLists.txt index fde0f233569f..1e2562087756 100644 --- a/src/drivers/uavcannode/CMakeLists.txt +++ b/src/drivers/uavcannode/CMakeLists.txt @@ -121,6 +121,8 @@ add_custom_command(OUTPUT px4_uavcan_dsdlc_run.stamp --outdir ${DSDLC_OUTPUT} ${DSDLC_INPUTS} #--verbose COMMAND ${CMAKE_COMMAND} -E touch px4_uavcan_dsdlc_run.stamp + MODULE_CONFIG + module.yaml DEPENDS ${DSDLC_INPUT_FILES} COMMENT "PX4 UAVCAN dsdl compiler" ) diff --git a/src/drivers/uavcannode/module.yaml b/src/drivers/uavcannode/module.yaml new file mode 100644 index 000000000000..6fcc5feb59c2 --- /dev/null +++ b/src/drivers/uavcannode/module.yaml @@ -0,0 +1,35 @@ +module_name: uavcannode +parameters: + - definitions: + CANNODE_BITRATE: + default: 1000000 + description: + short: UAVCAN CAN bus bitrate + max: 1000000 + min: 20000 + type: int32 + volatile: false + CANNODE_GPS_RTCM: + default: 0 + description: + short: Enable RTCM pub/sub + max: 1 + type: boolean + volatile: false + CANNODE_NODE_ID: + default: 120 + description: + long: Read the specs at http://uavcan.org to learn more about Node ID. + short: UAVCAN Node ID + max: 125 + min: 1 + type: int32 + volatile: false + CANNODE_TERM: + default: 0 + description: + short: CAN built-in bus termination + max: 1 + type: boolean + volatile: false + group: UAVCAN diff --git a/src/drivers/uavcannode/uavcannode_params.c b/src/drivers/uavcannode/uavcannode_params.c deleted file mode 100644 index 8e9a10e833d7..000000000000 --- a/src/drivers/uavcannode/uavcannode_params.c +++ /dev/null @@ -1,70 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2014-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * UAVCAN Node ID. - * - * Read the specs at http://uavcan.org to learn more about Node ID. - * - * @min 1 - * @max 125 - * @group UAVCAN - */ -PARAM_DEFINE_INT32(CANNODE_NODE_ID, 120); - -/** - * UAVCAN CAN bus bitrate. - * - * @min 20000 - * @max 1000000 - * @group UAVCAN - */ -PARAM_DEFINE_INT32(CANNODE_BITRATE, 1000000); - -/** - * CAN built-in bus termination - * - * @boolean - * @max 1 - * @group UAVCAN - */ -PARAM_DEFINE_INT32(CANNODE_TERM, 0); - -/** - * Enable RTCM pub/sub - * - * @boolean - * @max 1 - * @group UAVCAN - */ -PARAM_DEFINE_INT32(CANNODE_GPS_RTCM, 0); diff --git a/src/drivers/uwb/uwb_sr150/module.yaml b/src/drivers/uwb/uwb_sr150/module.yaml index 3442e138be0c..7155f340471f 100644 --- a/src/drivers/uwb/uwb_sr150/module.yaml +++ b/src/drivers/uwb/uwb_sr150/module.yaml @@ -5,49 +5,42 @@ serial_config: name: UWB_PORT_CFG group: UWB default: "" - parameters: - - group: UWB - definitions: - - UWB_INIT_OFF_X: - description: - short: UWB sensor X offset in body frame - long: UWB sensor positioning in relation to Drone in NED. X offset. A Positiv offset results in a Position o - type: float - unit: m - decimal: 2 - increment: 0.01 - default: 0.00 - - UWB_INIT_OFF_Y: - description: - short: UWB sensor Y offset in body frame - long: UWB sensor positioning in relation to Drone in NED. Y offset. - type: float - unit: m - decimal: 2 - increment: 0.01 - default: 0.00 - - UWB_INIT_OFF_Z: - description: - short: UWB sensor Y offset in body frame - long: UWB sensor positioning in relation to Drone in NED. Z offset. - type: float - unit: m - decimal: 2 - increment: 0.01 - default: 0.00 - - UWB_INIT_OFF_YAW: - description: - short: UWB sensor YAW offset in body frame - long: UWB sensor positioning in relation to Drone in NED. Yaw rotation in relation to direction of FMU. - type: float - unit: deg - decimal: 1 - increment: 0.1 - default: 0.00 - - + - group: UWB + definitions: + UWB_INIT_OFF_X: + description: + short: UWB sensor X offset in body frame + long: UWB sensor positioning in relation to Drone in NED. X offset. A Positiv offset results in a Position o + type: float + unit: m + decimal: 2 + increment: 0.01 + default: 0.00 + UWB_INIT_OFF_Y: + description: + short: UWB sensor Y offset in body frame + long: UWB sensor positioning in relation to Drone in NED. Y offset. + type: float + unit: m + decimal: 2 + increment: 0.01 + default: 0.00 + UWB_INIT_OFF_Z: + description: + short: UWB sensor Y offset in body frame + long: UWB sensor positioning in relation to Drone in NED. Z offset. + type: float + unit: m + decimal: 2 + increment: 0.01 + default: 0.00 + UWB_INIT_OFF_YAW: + description: + short: UWB sensor YAW offset in body frame + long: UWB sensor positioning in relation to Drone in NED. Yaw rotation in relation to direction of FMU. + type: float + unit: deg + decimal: 1 + increment: 0.1 + default: 0.00 diff --git a/src/lib/battery/battery_params_deprecated.c b/src/lib/battery/battery_params_deprecated.c index 829e636c2c27..26ac03d8880a 100644 --- a/src/lib/battery/battery_params_deprecated.c +++ b/src/lib/battery/battery_params_deprecated.c @@ -41,7 +41,7 @@ * This parameter is deprecated. Please use BAT1_V_EMPTY instead. * * @group Battery Calibration - * @category system + * @category System */ PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.6f); @@ -49,7 +49,7 @@ PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.6f); * This parameter is deprecated. Please use BAT1_V_CHARGED instead. * * @group Battery Calibration - * @category system + * @category System */ PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.05f); @@ -57,7 +57,7 @@ PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.05f); * This parameter is deprecated. Please use BAT1_V_LOAD_DROP instead. * * @group Battery Calibration - * @category system + * @category System */ PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.3f); @@ -65,6 +65,6 @@ PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.3f); * This parameter is deprecated. Please use BAT1_N_CELLS instead. * * @group Battery Calibration - * @category system + * @category System */ PARAM_DEFINE_INT32(BAT_N_CELLS, 3); diff --git a/src/lib/parameters/parameters_injected.xml b/src/lib/parameters/parameters_injected.xml index b927adc28924..7d7d9aa4d529 100644 --- a/src/lib/parameters/parameters_injected.xml +++ b/src/lib/parameters/parameters_injected.xml @@ -151,7 +151,7 @@ - + GNSS satellite count warning threshold Set the device health to Warning if the number of satellites used in the GNSS solution is below this threshold. Zero disables the feature diff --git a/src/lib/parameters/px4params/injectxmlparams.py b/src/lib/parameters/px4params/injectxmlparams.py index 060015a170ab..c2a9d3cc389e 100755 --- a/src/lib/parameters/px4params/injectxmlparams.py +++ b/src/lib/parameters/px4params/injectxmlparams.py @@ -47,17 +47,17 @@ def __init__(self, injected_xml_filename): #get param info stored as child tags for child in iparam: if child.tag in valid_field_tags: - new_param.SetField(child.tag, child.text) + new_param.fields[child.tag] = child.text elif child.tag == 'values': for value in child: - new_param.SetEnumValue(value.get('code'), value.text) + new_param.enum[value.get('code')] = value.text elif child.tag == 'bitmask': for bit in child: new_param.SetBitmaskBit(bit.get('index'), bit.text) else: not_handled_parameter_tags.add(child.tag) - imported_group.AddParameter(new_param) + imported_group.parameters.append(new_param) self.groups.append(imported_group) diff --git a/src/lib/parameters/px4params/jsonout.py b/src/lib/parameters/px4params/jsonout.py index a8052e0f3739..9574b3d926f4 100644 --- a/src/lib/parameters/px4params/jsonout.py +++ b/src/lib/parameters/px4params/jsonout.py @@ -30,36 +30,39 @@ def __init__(self, groups, board, inject_xml_file_name): last_param_name = "" board_specific_param_set = False for group in groups: - group_name=group.GetName() + group_name=group.name def get_typed_value(value: str, type_name: str): if type_name == 'Float': return float(value) if type_name == 'Int32': return int(value) return value - for param in group.GetParams(): - if (last_param_name == param.GetName() and not board_specific_param_set) or last_param_name != param.GetName(): + for param in sorted(group.parameters): + if (last_param_name == param.name and not board_specific_param_set) or last_param_name != param.name: curr_param=dict() - curr_param['name'] = param.GetName() - type_name = param.GetType().capitalize() + curr_param['name'] = param.name + type_name = param.type.capitalize() curr_param['type'] = type_name if not type_name in allowed_types: print("Error: %s type not supported: curr_param['type']" % (curr_param['name'],curr_param['type']) ) sys.Exit(1) - curr_param['default'] = get_typed_value(param.GetDefault(), type_name) + curr_param['default'] = get_typed_value(param.default, type_name) curr_param['group'] = group_name - if param.GetCategory(): - curr_param['category'] = param.GetCategory() + if param.category != "": + curr_param['category'] = param.category else: curr_param['category'] = 'Standard' - if param.GetVolatile(): + if param.volatile: curr_param['volatile'] = True - last_param_name = param.GetName() - for code in param.GetFieldCodes(): - value = param.GetFieldValue(code) + last_param_name = param.name + for code in param.field_keys: + value = param.fields.get(code, "") + # XML parsing returns empty fields as None + if value is None: + value = "" if code == "board": if value == board: board_specific_param_set = True @@ -80,32 +83,32 @@ def get_typed_value(value: str, type_name: str): sys.exit(1) - if last_param_name != param.GetName(): + if last_param_name != param.name: board_specific_param_set = False - enum_codes=param.GetEnumCodes() or '' # Gets numerical values for parameter. + enum_codes=sorted(param.enum.keys(), key=float) if enum_codes: enum_codes=sorted(enum_codes,key=float) codes_list=list() for item in enum_codes: code_dict=dict() code_dict['value']=get_typed_value(item, type_name) - code_dict['description']=param.GetEnumValue(item) + code_dict['description']=param.enum.get(item, "") codes_list.append(code_dict) curr_param['values'] = codes_list - elif param.GetBoolean(): + elif param.boolean: curr_param['values'] = [ { 'value': 0, 'description': 'Disabled' }, { 'value': 1, 'description': 'Enabled' } ] - if len(param.GetBitmaskList()) > 0: + if len(param.bitmask.keys()) > 0: bitmasks_list=list() - for index in param.GetBitmaskList(): + for index in sorted(param.bitmask.keys(), key=float): bitmask_dict=dict() bitmask_dict['index']=int(index) - bitmask_dict['description']=param.GetBitmaskBit(index) + bitmask_dict['description']=param.bitmask.get(index, "") bitmasks_list.append(bitmask_dict) curr_param['bitmask'] = bitmasks_list diff --git a/src/lib/parameters/px4params/markdownout.py b/src/lib/parameters/px4params/markdownout.py index eb1690e7cdbf..aa3b8a485f11 100644 --- a/src/lib/parameters/px4params/markdownout.py +++ b/src/lib/parameters/px4params/markdownout.py @@ -32,7 +32,7 @@ def __init__(self, groups): ) for group in groups: - result += '## %s\n\n' % group.GetName() + result += '## %s\n\n' % group.name result += ( """ @@ -42,18 +42,18 @@ def __init__(self, groups): """ ) - for param in group.GetParams(): - code = param.GetName() - name = param.GetFieldValue("short_desc") or '' - long_desc = param.GetFieldValue("long_desc") or '' - min_val = param.GetFieldValue("min") or '' - max_val = param.GetFieldValue("max") or '' - increment = param.GetFieldValue("increment") or '' - def_val = param.GetDefault() or '' - unit = param.GetFieldValue("unit") or '' - type = param.GetType() - is_boolean = param.GetBoolean() - reboot_required = param.GetFieldValue("reboot_required") or '' + for param in group.parameters: + code = param.name + name = param.fields.get("short_desc", "") + long_desc = param.fields.get("long_desc", "") + min_val = param.fields.get("min", "") + max_val = param.fields.get("max", "") + increment = param.fields.get("increment", "") + def_val = param.default + unit = param.fields.get("unit", "") + type = param.type + is_boolean = param.boolean + reboot_required = param.fields.get("reboot_required", "") #board = param.GetFieldValue("board") or '' ## Disabled as no board values are defined in any parameters! #decimal = param.GetFieldValue("decimal") or '' #Disabled as is intended for GCS not people #field_codes = param.GetFieldCodes() ## Disabled as not needed for display. @@ -82,24 +82,24 @@ def __init__(self, groups): if reboot_required: reboot_required='

Reboot required: %s

\n' % reboot_required - enum_codes=param.GetEnumCodes() or '' # Gets numerical values for parameter. + enum_codes=param.enum.keys() or '' # Gets numerical values for parameter. enum_output='' # Format codes and their descriptions for display. if enum_codes: enum_output+='Values:
    ' enum_codes=sorted(enum_codes,key=float) for item in enum_codes: - enum_output+='\n
  • %s: %s
  • \n' % (item, param.GetEnumValue(item)) + enum_output+='\n
  • %s: %s
  • \n' % (item, param.enum[item]) enum_output+='
\n' - bitmask_list=param.GetBitmaskList() #Gets bitmask values for parameter + bitmask_list=param.bitmask.keys() #Gets bitmask values for parameter bitmask_output='' #Format bitmask values if bitmask_list: bitmask_output+='Bitmask:
    ' for bit in bitmask_list: - bit_text = param.GetBitmaskBit(bit) + bit_text = param.bitmask[bit] bitmask_output+='
  • %s: %s
  • \n' % (bit, bit_text) bitmask_output+='
\n' diff --git a/src/lib/parameters/px4params/srcparser.py b/src/lib/parameters/px4params/srcparser.py index 1ed72860a6da..726fa36b9b93 100644 --- a/src/lib/parameters/px4params/srcparser.py +++ b/src/lib/parameters/px4params/srcparser.py @@ -1,174 +1,69 @@ import sys +from typing import Dict, List + import re import math +from dataclasses import dataclass, field global default_var default_var = {} -class ParameterGroup(object): - """ - Single parameter group - """ - def __init__(self, name): - self.name = name - self.no_code_generation = False #for injected parameters - self.params = [] - def AddParameter(self, param): - """ - Add parameter to the group - """ - self.params.append(param) - - def GetName(self): - """ - Get parameter group name - """ - return self.name +# define sorting order of the fields +PRIORITIES = { + "board": 9, + "short_desc": 8, + "long_desc": 7, + "min": 5, + "max": 4, + "unit": 3, + "decimal": 2, + # all others == 0 (sorted alphabetically) +} - def GetParams(self): - """ - Returns the parsed list of parameters. Every parameter is a Parameter - object. Note that returned object is not a copy. Modifications affect - state of the parser. - """ - return sorted(self.params, key=lambda param: param.name) -class Parameter(object): +@dataclass +class Parameter: """ Single parameter """ - # Define sorting order of the fields - priority = { - "board": 9, - "short_desc": 8, - "long_desc": 7, - "min": 5, - "max": 4, - "unit": 3, - "decimal": 2, - # all others == 0 (sorted alphabetically) - } - - def __init__(self, name, type, default = ""): - self.fields = {} - self.values = {} - self.bitmask = {} - self.name = name - self.type = type - self.default = default - self.category = "" - self.volatile = False - self.boolean = False - - def GetName(self): - return self.name + name: str + type: str + fields: Dict[str, str] = field(init=False, default_factory=dict) + default: str = "" + category: str = "" + enum: Dict[str, str] = field(init=False, default_factory=dict) + bitmask: Dict[str, str] = field(init=False, default_factory=dict) + volatile: bool = False + boolean: bool = False - def GetType(self): - return self.type + def __lt__(self, other): + return self.name < other.name - def GetDefault(self): - return self.default - - def GetCategory(self): - return self.category.title() - - def GetVolatile(self): - return self.volatile - - def GetBoolean(self): - return self.boolean - - def SetField(self, code, value): - """ - Set named field value - """ - self.fields[code] = value - - def SetEnumValue(self, code, value): - """ - Set named enum value - """ - self.values[code] = value - - def SetBitmaskBit(self, index, bit): - """ - Set named enum value - """ - self.bitmask[index] = bit - - def SetVolatile(self): - """ - Set volatile flag - """ - self.volatile = True - - def SetBoolean(self): - """ - Set boolean flag - """ - self.boolean = True - - def SetCategory(self, category): - """ - Set param category - """ - self.category = category - - def GetFieldCodes(self): + @property + def field_keys(self) -> List[str]: """ Return list of existing field codes in convenient order """ keys = self.fields.keys() keys = sorted(keys) - keys = sorted(keys, key=lambda x: self.priority.get(x, 0), reverse=True) + keys = sorted(keys, key=lambda x: PRIORITIES.get(x, 0), reverse=True) return keys - def GetFieldValue(self, code): - """ - Return value of the given field code or None if not found. - """ - fv = self.fields.get(code) - if not fv: - # required because python 3 sorted does not accept None - return "" - return fv - - def GetEnumCodes(self): - """ - Return list of existing value codes in convenient order - """ - return sorted(self.values.keys(), key=float) - def GetEnumValue(self, code): - """ - Return value of the given enum code or None if not found. - """ - fv = self.values.get(code) - if not fv: - # required because python 3 sorted does not accept None - return "" - return fv +@dataclass +class ParameterGroup: + """ + Single parameter group + """ - def GetBitmaskList(self): - """ - Return list of existing bitmask codes in convenient order - """ - keys = self.bitmask.keys() - return sorted(keys, key=float) + name: str + parameters: List[Parameter] = field(init=False, default_factory=list) + no_code_generation: bool = False - def GetBitmaskBit(self, index): - """ - Return value of the given bitmask code or None if not found. - """ - fv = self.bitmask.get(index) - if not fv: - # required because python 3 sorted does not accept None - return "" - return fv.strip() -class SourceParser(object): +class SourceParser: """ Parses provided data and stores all found parameters internally. """ @@ -186,7 +81,9 @@ class SourceParser(object): re_remove_dots = re.compile(r'\.+$') re_remove_carriage_return = re.compile('\n+') - valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "increment", "reboot_required", "value", "boolean", "bit", "category", "volatile"]) + valid_tags = set(["group", "board", "min", "max", "unit", "decimal", + "increment", "reboot_required", "value", "boolean", + "bit", "category", "volatile"]) # Order of parameter groups priority = { @@ -197,7 +94,7 @@ class SourceParser(object): def __init__(self): self.param_groups = {} - def Parse(self, contents): + def parse(self, contents): """ Incrementally parse program contents and append all found parameters to the list. @@ -238,11 +135,13 @@ def Parse(self, contents): if m: tag, desc = m.group(1, 2) if (tag == "value"): - # Take the meta info string and split the code and description + # Take the meta info string and split + # the code and description metainfo = desc.split(" ", 1) def_values[metainfo[0]] = metainfo[1] elif (tag == "bit"): - # Take the meta info string and split the code and description + # Take the meta info string and split + # the code and description metainfo = desc.split(" ", 1) def_bitmask[metainfo[0]] = metainfo[1] else: @@ -270,8 +169,8 @@ def Parse(self, contents): raise AssertionError( "Invalid parser state: %s" % state) elif not last_comment_line: - # Invalid comment line (inside comment, but not starting with - # "*" or "*/". Reset parsed content. + # Invalid comment line (inside comment, but not + # startin with "*" or "*/". Reset parsed content. state = None if last_comment_line: state = "comment-processed" @@ -283,7 +182,7 @@ def Parse(self, contents): m = self.re_px4_param_default_definition.match(line) # Default value handling if m: - name_m, defval_m = m.group(1,2) + name_m, defval_m = m.group(1, 2) default_var[name_m] = defval_m m = self.re_parameter_definition.match(line) if m: @@ -298,8 +197,8 @@ def Parse(self, contents): # Remove trailing type specifier from numbers: 0.1f => 0.1 if defval != "" and self.re_is_a_number.match(defval): defval = self.re_cut_type_specifier.sub('', defval) - param = Parameter(name, tp, defval) - param.SetField("short_desc", name) + param = Parameter(name=name, type=tp, default=defval) + param.fields["short_desc"] = name # If comment was found before the parameter declaration, # inject its data into the newly created parameter. group = "Miscellaneous" @@ -309,43 +208,36 @@ def Parse(self, contents): raise Exception('short description must be a single line (parameter: {:})'.format(name)) if len(short_desc) > 150: raise Exception('short description too long (150 max, is {:}, parameter: {:})'.format(len(short_desc), name)) - param.SetField("short_desc", self.re_remove_dots.sub('', short_desc)) + param.fields["short_desc"] = self.re_remove_dots.sub('', short_desc) if long_desc is not None: long_desc = self.re_remove_carriage_return.sub(' ', long_desc) - param.SetField("long_desc", long_desc) + param.fields["long_desc"] = long_desc for tag in tags: if tag == "group": group = tags[tag] elif tag == "volatile": - param.SetVolatile() + param.volatile = True elif tag == "category": - param.SetCategory(tags[tag]) + param.category = tags[tag] elif tag == "boolean": - param.SetBoolean() + param.boolean = True elif tag not in self.valid_tags: sys.stderr.write("Skipping invalid documentation tag: '%s'\n" % tag) return False else: - param.SetField(tag, tags[tag]) + param.fields[tag] = tags[tag] for def_value in def_values: - param.SetEnumValue(def_value, def_values[def_value]) + param.enum[def_value] = def_values[def_value] for def_bit in def_bitmask: - param.SetBitmaskBit(def_bit, def_bitmask[def_bit]) + param.bitmask[def_bit] = def_bitmask[def_bit] # Store the parameter if group not in self.param_groups: self.param_groups[group] = ParameterGroup(group) - self.param_groups[group].AddParameter(param) + self.param_groups[group].parameters.append(param) state = None return True - def IsNumber(self, numberString): - try: - float(numberString) - return True - except ValueError: - return False - - def Validate(self): + def validate(self): """ Validates the parameter meta data. """ @@ -366,13 +258,14 @@ def Validate(self): 'N/(m/s)', 'Nm/rad', 'Nm/(rad/s)', 'Nm', 'N', 'RPM', 'normalized_thrust/s', 'normalized_thrust', 'norm', 'SD','']) - for group in self.GetParamGroups(): - for param in group.GetParams(): - name = param.GetName() + + for group in self.parameter_groups: + for param in sorted(group.parameters): + name = param.name if len(name) > 16: sys.stderr.write("Parameter Name {0} is too long (Limit is 16)\n".format(name)) return False - board = param.GetFieldValue("board") + board = param.fields.get("board", "") # Check for duplicates name_plus_board = name + "+" + board for seenParamName in seenParamNames: @@ -381,60 +274,70 @@ def Validate(self): return False seenParamNames.append(name_plus_board) # Validate values - default = param.GetDefault() - min = param.GetFieldValue("min") - max = param.GetFieldValue("max") - units = param.GetFieldValue("unit") + default = param.default + min = param.fields.get("min", "") + max = param.fields.get("max", "") + units = param.fields.get("unit", "") if units not in allowedUnits: sys.stderr.write("Invalid unit in {0}: {1}\n".format(name, units)) return False #sys.stderr.write("{0} default:{1} min:{2} max:{3}\n".format(name, default, min, max)) - if default != "" and not self.IsNumber(default): + if default != "" and not self.is_number(default): sys.stderr.write("Default value not number: {0} {1}\n".format(name, default)) return False # if default != "" and "." not in default: # sys.stderr.write("Default value does not contain dot (e.g. 10 needs to be written as 10.0): {0} {1}\n".format(name, default)) # return False if min != "": - if not self.IsNumber(min): + if not self.is_number(default): sys.stderr.write("Min value not number: {0} {1}\n".format(name, min)) return False if default != "" and float(default) < float(min): sys.stderr.write("Default value is smaller than min: {0} default:{1} min:{2}\n".format(name, default, min)) return False if max != "": - if not self.IsNumber(max): + if not self.is_number(max): sys.stderr.write("Max value not number: {0} {1}\n".format(name, max)) return False if default != "" and float(default) > float(max): sys.stderr.write("Default value is larger than max: {0} default:{1} max:{2}\n".format(name, default, max)) return False - for code in param.GetEnumCodes(): - if not self.IsNumber(code): - sys.stderr.write("Min value not number: {0} {1}\n".format(name, code)) - return False - if param.GetEnumValue(code) == "": - sys.stderr.write("Description for enum value is empty: {0} {1}\n".format(name, code)) - return False - for index in param.GetBitmaskList(): - if not self.IsNumber(index): - sys.stderr.write("bit value not number: {0} {1}\n".format(name, index)) - return False - if not int(min) <= math.pow(2, int(index)) <= int(max): - sys.stderr.write("Bitmask bit must be between {0} and {1}: {2} {3}\n".format(min, max, name, math.pow(2, int(index)))) - return False - if param.GetBitmaskBit(index) == "": - sys.stderr.write("Description for bitmask bit is empty: {0} {1}\n".format(name, index)) - return False + for code in sorted(param.enum, key=float): + if not self.is_number(code): + sys.stderr.write("Min value not number: {0} {1}\n".format(name, code)) + return False + if param.enum.get(code, "") == "": + sys.stderr.write("Description for enum value is empty: {0} {1}\n".format(name, code)) + return False + for index in sorted(param.bitmask.keys(), key=float): + if not self.is_number(index): + sys.stderr.write("bit value not number: {0} {1}\n".format(name, index)) + return False + if not int(min) <= math.pow(2, int(index)) <= int(max): + sys.stderr.write("Bitmask bit must be between {0} and {1}: {2} {3}\n".format(min, max, name, math.pow(2, int(index)))) + return False + if param.bitmask.get(index, "") == "": + sys.stderr.write("Description for bitmask bit is empty: {0} {1}\n".format(name, index)) + return False return True - def GetParamGroups(self): + def is_number(self, num): + try: + float(num) + return True + except ValueError: + return False + + @property + def parameter_groups(self) -> List[ParameterGroup]: """ Returns the parsed list of parameters. Every parameter is a Parameter object. Note that returned object is not a copy. Modifications affect state of the parser. """ groups = self.param_groups.values() - groups = sorted(groups, key=lambda x: x.GetName()) - groups = sorted(groups, key=lambda x: self.priority.get(x.GetName(), 0), reverse=True) + groups = sorted(groups, key=lambda x: x.name) + groups = sorted(groups, key=lambda x: self.priority.get(x.name, 0), + reverse=True) + return groups diff --git a/src/lib/parameters/px4params/srcscanner.py b/src/lib/parameters/px4params/srcscanner.py index 8be54a245008..52573009d469 100644 --- a/src/lib/parameters/px4params/srcscanner.py +++ b/src/lib/parameters/px4params/srcscanner.py @@ -12,7 +12,7 @@ class SourceScanner(object): def ScanDir(self, srcdirs, parser): """ Scans provided path and passes all found contents to the parser using - parser.Parse method. + parser.parse method. """ extensions1 = tuple([".h"]) extensions2 = tuple([".c"]) @@ -32,7 +32,7 @@ def ScanDir(self, srcdirs, parser): def ScanFile(self, path, parser): """ Scans provided file and passes its contents to the parser using - parser.Parse method. + parser.parse method. """ with codecs.open(path, 'r', 'utf-8') as f: @@ -42,4 +42,4 @@ def ScanFile(self, path, parser): contents = '' print('Failed reading file: %s, skipping content.' % path) pass - return parser.Parse(contents) + return parser.parse(contents) diff --git a/src/lib/parameters/px4params/xmlout.py b/src/lib/parameters/px4params/xmlout.py index ecbd5a3dc6f5..ffeb38e3755d 100644 --- a/src/lib/parameters/px4params/xmlout.py +++ b/src/lib/parameters/px4params/xmlout.py @@ -30,24 +30,24 @@ def __init__(self, groups, board): board_specific_param_set = False for group in groups: xml_group = ET.SubElement(xml_parameters, "group") - xml_group.attrib["name"] = group.GetName() + xml_group.attrib["name"] = group.name if group.no_code_generation: xml_group.attrib["no_code_generation"] = group.no_code_generation - for param in group.GetParams(): - if (last_param_name == param.GetName() and not board_specific_param_set) or last_param_name != param.GetName(): + for param in sorted(group.parameters): + if (last_param_name == param.name and not board_specific_param_set) or last_param_name != param.name: xml_param = ET.SubElement(xml_group, "parameter") - xml_param.attrib["name"] = param.GetName() - xml_param.attrib["default"] = param.GetDefault() - xml_param.attrib["type"] = param.GetType() - if param.GetVolatile(): + xml_param.attrib["name"] = param.name + xml_param.attrib["default"] = param.default + xml_param.attrib["type"] = param.type + if param.volatile: xml_param.attrib["volatile"] = "true" - if param.GetBoolean(): + if param.boolean: xml_param.attrib["boolean"] = "true" - if (param.GetCategory()): - xml_param.attrib["category"] = param.GetCategory() - last_param_name = param.GetName() - for code in param.GetFieldCodes(): - value = param.GetFieldValue(code) + if param.category != "": + xml_param.attrib["category"] = param.category.title() + last_param_name = param.name + for code in param.field_keys: + value = param.fields.get(code, "") if code == "board": if value == board: board_specific_param_set = True @@ -58,22 +58,22 @@ def __init__(self, groups, board): else: xml_field = ET.SubElement(xml_param, code) xml_field.text = value - if last_param_name != param.GetName(): + if last_param_name != param.name: board_specific_param_set = False - if len(param.GetEnumCodes()) > 0: + if len(param.enum.keys()) > 0: xml_values = ET.SubElement(xml_param, "values") - for code in param.GetEnumCodes(): + for code in sorted(param.enum.keys(), key=float): xml_value = ET.SubElement(xml_values, "value") xml_value.attrib["code"] = code; - xml_value.text = param.GetEnumValue(code) + xml_value.text = param.enum[code] - if len(param.GetBitmaskList()) > 0: + if len(param.bitmask.keys()) > 0: xml_values = ET.SubElement(xml_param, "bitmask") - for index in param.GetBitmaskList(): + for index in sorted(param.bitmask.keys(), key=float): xml_value = ET.SubElement(xml_values, "bit") xml_value.attrib["index"] = index; - xml_value.text = param.GetBitmaskBit(index) + xml_value.text = param.bitmask.get(index, "") indent(xml_parameters) self.xml_document = ET.ElementTree(xml_parameters) diff --git a/src/lib/parameters/px_process_params.py b/src/lib/parameters/px_process_params.py index 0c777bb1d4ee..33090f2d6daa 100755 --- a/src/lib/parameters/px_process_params.py +++ b/src/lib/parameters/px_process_params.py @@ -1,4 +1,5 @@ #!/usr/bin/env python + ############################################################################ # # Copyright (C) 2013-2017 PX4 Development Team. All rights reserved. @@ -47,6 +48,7 @@ import sys import os import argparse + from px4params import srcscanner, srcparser, injectxmlparams, xmlout, markdownout, jsonout import lzma #to create .xz file @@ -130,9 +132,9 @@ def main(): if not scanner.ScanDir(args.src_path, parser): sys.exit(1) - if not parser.Validate(): + if not parser.validate(): sys.exit(1) - param_groups = parser.GetParamGroups() + param_groups = parser.parameter_groups if len(param_groups) == 0: print("Warning: no parameters found") @@ -146,10 +148,10 @@ def main(): override_dict = json.loads(args.overrides) if len(override_dict.keys()) > 0: for group in param_groups: - for param in group.GetParams(): - name = param.GetName() + for param in group.parameters: + name = param.name if name in override_dict.keys(): - val = str(override_dict[param.GetName()]) + val = str(override_dict[param.name]) param.default = val print("OVERRIDING {:s} to {:s}!!!!!".format(name, val)) diff --git a/src/modules/airspeed_selector/CMakeLists.txt b/src/modules/airspeed_selector/CMakeLists.txt index fb3d24f8699e..1e3b95c7a48b 100644 --- a/src/modules/airspeed_selector/CMakeLists.txt +++ b/src/modules/airspeed_selector/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( airspeed_selector_main.cpp AirspeedValidator.cpp AirspeedValidator.hpp + MODULE_CONFIG + module.yaml DEPENDS wind_estimator ) diff --git a/src/modules/airspeed_selector/airspeed_selector_params.c b/src/modules/airspeed_selector/airspeed_selector_params.c deleted file mode 100644 index 8e9de8e86d95..000000000000 --- a/src/modules/airspeed_selector/airspeed_selector_params.c +++ /dev/null @@ -1,229 +0,0 @@ - -/** - * Airspeed Selector: Wind estimator wind process noise noise spectral density - * - * Wind process noise of the internal wind estimator(s) of the airspeed selector. - * When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. - * - * @min 0 - * @max 1 - * @unit m/s^2/sqrt(Hz) - * @decimal 2 - * @group Airspeed Validator - */ -PARAM_DEFINE_FLOAT(ASPD_WIND_NSD, 1.e-2f); - -/** - * Airspeed Selector: Wind estimator true airspeed scale process noise spectral density - * - * Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. - * When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second. - * - * @min 0 - * @max 0.1 - * @unit 1/s/sqrt(Hz) - * @decimal 5 - * @group Airspeed Validator - */ -PARAM_DEFINE_FLOAT(ASPD_SCALE_NSD, 0.0001f); - -/** - * Airspeed Selector: Wind estimator true airspeed measurement noise - * - * True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector. - * - * @min 0 - * @max 4 - * @unit m/s - * @decimal 1 - * @group Airspeed Validator - */ -PARAM_DEFINE_FLOAT(ASPD_TAS_NOISE, 1.4f); - -/** - * Airspeed Selector: Wind estimator sideslip measurement noise - * - * Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector. - * - * @min 0 - * @max 1 - * @unit rad - * @decimal 3 - * @group Airspeed Validator - */ -PARAM_DEFINE_FLOAT(ASPD_BETA_NOISE, 0.3f); - -/** - * Airspeed Selector: Gate size for true airspeed fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @min 1 - * @max 5 - * @unit SD - * @group Airspeed Validator - */ -PARAM_DEFINE_INT32(ASPD_TAS_GATE, 3); - -/** - * Airspeed Selector: Gate size for sideslip angle fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @min 1 - * @max 5 - * @unit SD - * @group Airspeed Validator - */ -PARAM_DEFINE_INT32(ASPD_BETA_GATE, 1); - -/** - * Controls when to apply the new estimated airspeed scale(s) - * - * @value 0 Do not automatically apply the estimated scale - * @value 1 Apply the estimated scale after disarm - * @value 2 Apply the estimated scale in air - * @group Airspeed Validator - */ -PARAM_DEFINE_INT32(ASPD_SCALE_APPLY, 2); - -/** - * Scale of airspeed sensor 1 - * - * This is the scale IAS --> CAS of the first airspeed sensor instance - * - * @min 0.5 - * @max 2.0 - * @decimal 2 - * @reboot_required true - * @group Airspeed Validator - * @volatile - */ -PARAM_DEFINE_FLOAT(ASPD_SCALE_1, 1.0f); - -/** - * Scale of airspeed sensor 2 - * - * This is the scale IAS --> CAS of the second airspeed sensor instance - * - * @min 0.5 - * @max 2.0 - * @decimal 2 - * @reboot_required true - * @group Airspeed Validator - * @volatile - */ -PARAM_DEFINE_FLOAT(ASPD_SCALE_2, 1.0f); - -/** - * Scale of airspeed sensor 3 - * - * This is the scale IAS --> CAS of the third airspeed sensor instance - * - * @min 0.5 - * @max 2.0 - * @decimal 2 - * @reboot_required true - * @group Airspeed Validator - * @volatile - */ -PARAM_DEFINE_FLOAT(ASPD_SCALE_3, 1.0f); - -/** - * Index or primary airspeed measurement source - * - * @value -1 Disabled - * @value 0 Groundspeed minus windspeed - * @value 1 First airspeed sensor - * @value 2 Second airspeed sensor - * @value 3 Third airspeed sensor - * - * @reboot_required true - * @group Airspeed Validator - */ -PARAM_DEFINE_INT32(ASPD_PRIMARY, 1); - - -/** - * Enable checks on airspeed sensors - * - * Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0. - * Note that the data missing check is enabled if any of the options is set. - * - * @min 0 - * @max 15 - * @bit 0 Only data missing check (triggers if more than 1s no data) - * @bit 1 Data stuck (triggers if data is exactly constant for 2s) - * @bit 2 Innovation check (see ASPD_FS_INNOV) - * @bit 3 Load factor check (triggers if measurement is below stall speed) - * @group Airspeed Validator - */ -PARAM_DEFINE_INT32(ASPD_DO_CHECKS, 7); - -/** - * Enable fallback to sensor-less airspeed estimation - * - * If set to true and airspeed checks are enabled, it will use a sensor-less airspeed estimation based on groundspeed - * minus windspeed if no other airspeed sensor available to fall back to. - * - * @value 0 Disable fallback to sensor-less estimation - * @value 1 Enable fallback to sensor-less estimation - * @boolean - * @group Airspeed Validator - */ -PARAM_DEFINE_INT32(ASPD_FALLBACK_GW, 0); - -/** - * Airspeed failure innovation threshold - * - * This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, - * smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) - * and measured airspeed. - * The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter. - * - * @unit m/s - * @min 0.5 - * @max 10.0 - * @decimal 1 - * @group Airspeed Validator - */ -PARAM_DEFINE_FLOAT(ASPD_FS_INNOV, 5.f); - -/** - * Airspeed failure innovation integral threshold - * - * This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. - * Larger values make the check less sensitive, smaller positive values make it more sensitive. - * - * @unit m - * @min 0.0 - * @max 50.0 - * @decimal 1 - * @group Airspeed Validator - */ -PARAM_DEFINE_FLOAT(ASPD_FS_INTEG, 10.f); - -/** - * Airspeed failsafe stop delay - * - * Delay before stopping use of airspeed sensor if checks indicate sensor is bad. - * - * @unit s - * @group Airspeed Validator - * @min 1 - * @max 10 - */ -PARAM_DEFINE_INT32(ASPD_FS_T_STOP, 2); - -/** - * Airspeed failsafe start delay - * - * Delay before switching back to using airspeed sensor if checks indicate sensor is good. - * Set to a negative value to disable the re-enabling in flight. - * - * @unit s - * @group Airspeed Validator - * @min -1 - * @max 1000 - */ -PARAM_DEFINE_INT32(ASPD_FS_T_START, -1); diff --git a/src/modules/airspeed_selector/module.yaml b/src/modules/airspeed_selector/module.yaml new file mode 100644 index 000000000000..24b0fba8bd27 --- /dev/null +++ b/src/modules/airspeed_selector/module.yaml @@ -0,0 +1,213 @@ +module_name: airspeed_selector +parameters: +- definitions: + ASPD_BETA_GATE: + default: 1 + description: + long: Sets the number of standard deviations used by the innovation consistency + test. + short: 'Airspeed Selector: Gate size for sideslip angle fusion' + max: 5 + min: 1 + type: int32 + unit: SD + volatile: false + ASPD_BETA_NOISE: + decimal: 3 + default: 0.3 + description: + long: Sideslip measurement noise of the internal wind estimator(s) of the + airspeed selector. + short: 'Airspeed Selector: Wind estimator sideslip measurement noise' + max: 1 + min: 0 + type: float + unit: rad + volatile: false + ASPD_DO_CHECKS: + bit: + 0: Only data missing check (triggers if more than 1s no data) + 1: Data stuck (triggers if data is exactly constant for 2s) + 2: Innovation check (see ASPD_FS_INNOV) + 3: Load factor check (triggers if measurement is below stall speed) + default: 7 + description: + long: Controls which checks are run to check airspeed data for validity. Only + applied if ASPD_PRIMARY > 0. Note that the data missing check is enabled + if any of the options is set. + short: Enable checks on airspeed sensors + max: 15 + min: 0 + type: bitmask + volatile: false + ASPD_FALLBACK_GW: + default: 0 + description: + long: If set to true and airspeed checks are enabled, it will use a sensor-less + airspeed estimation based on groundspeed minus windspeed if no other airspeed + sensor available to fall back to. + short: Enable fallback to sensor-less airspeed estimation + type: enum + values: + 0: Disable fallback to sensor-less estimation + 1: Enable fallback to sensor-less estimation + volatile: false + ASPD_FS_INNOV: + decimal: 1 + default: 5.0 + description: + long: This specifies the minimum airspeed innovation required to trigger a + failsafe. Larger values make the check less sensitive, smaller values make + it more sensitive. Large innovations indicate an inconsistency between predicted + (groundspeed - windspeeed) and measured airspeed. The time required to detect + a fault when the threshold is exceeded depends on the size of the exceedance + and is controlled by the ASPD_FS_INTEG parameter. + short: Airspeed failure innovation threshold + max: 10.0 + min: 0.5 + type: float + unit: m/s + volatile: false + ASPD_FS_INTEG: + decimal: 1 + default: 10.0 + description: + long: This sets the time integral of airspeed innovation exceedance above + ASPD_FS_INNOV required to trigger a failsafe. Larger values make the check + less sensitive, smaller positive values make it more sensitive. + short: Airspeed failure innovation integral threshold + max: 50.0 + min: 0.0 + type: float + unit: m + volatile: false + ASPD_FS_T_START: + default: -1 + description: + long: Delay before switching back to using airspeed sensor if checks indicate + sensor is good. Set to a negative value to disable the re-enabling in flight. + short: Airspeed failsafe start delay + max: 1000 + min: -1 + type: int32 + unit: s + volatile: false + ASPD_FS_T_STOP: + default: 2 + description: + long: Delay before stopping use of airspeed sensor if checks indicate sensor + is bad. + short: Airspeed failsafe stop delay + max: 10 + min: 1 + type: int32 + unit: s + volatile: false + ASPD_PRIMARY: + default: 1 + description: + short: Index or primary airspeed measurement source + reboot_required: true + type: enum + values: + -1: Disabled + 0: Groundspeed minus windspeed + 1: First airspeed sensor + 2: Second airspeed sensor + 3: Third airspeed sensor + volatile: false + ASPD_SCALE_1: + decimal: 2 + default: 1.0 + description: + long: This is the scale IAS --> CAS of the first airspeed sensor instance + short: Scale of airspeed sensor 1 + max: 2.0 + min: 0.5 + reboot_required: true + type: float + volatile: true + ASPD_SCALE_2: + decimal: 2 + default: 1.0 + description: + long: This is the scale IAS --> CAS of the second airspeed sensor instance + short: Scale of airspeed sensor 2 + max: 2.0 + min: 0.5 + reboot_required: true + type: float + volatile: true + ASPD_SCALE_3: + decimal: 2 + default: 1.0 + description: + long: This is the scale IAS --> CAS of the third airspeed sensor instance + short: Scale of airspeed sensor 3 + max: 2.0 + min: 0.5 + reboot_required: true + type: float + volatile: true + ASPD_SCALE_APPLY: + default: 2 + description: + short: Controls when to apply the new estimated airspeed scale(s) + type: enum + values: + 0: Do not automatically apply the estimated scale + 1: Apply the estimated scale after disarm + 2: Apply the estimated scale in air + volatile: false + ASPD_SCALE_NSD: + decimal: 5 + default: 0.0001 + description: + long: Airspeed scale process noise of the internal wind estimator(s) of the + airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) + increases by this amount every second. + short: 'Airspeed Selector: Wind estimator true airspeed scale process noise + spectral density' + max: 0.1 + min: 0 + type: float + unit: 1/s/sqrt(Hz) + volatile: false + ASPD_TAS_GATE: + default: 3 + description: + long: Sets the number of standard deviations used by the innovation consistency + test. + short: 'Airspeed Selector: Gate size for true airspeed fusion' + max: 5 + min: 1 + type: int32 + unit: SD + volatile: false + ASPD_TAS_NOISE: + decimal: 1 + default: 1.4 + description: + long: True airspeed measurement noise of the internal wind estimator(s) of + the airspeed selector. + short: 'Airspeed Selector: Wind estimator true airspeed measurement noise' + max: 4 + min: 0 + type: float + unit: m/s + volatile: false + ASPD_WIND_NSD: + decimal: 2 + default: 0.01 + description: + long: Wind process noise of the internal wind estimator(s) of the airspeed + selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) + increases by this amount every second. + short: 'Airspeed Selector: Wind estimator wind process noise noise spectral + density' + max: 1 + min: 0 + type: float + unit: m/s^2/sqrt(Hz) + volatile: false + group: Airspeed Validator diff --git a/src/modules/angular_velocity_controller/CMakeLists.txt b/src/modules/angular_velocity_controller/CMakeLists.txt index 4cfc369db7ba..a002d18d8ce9 100644 --- a/src/modules/angular_velocity_controller/CMakeLists.txt +++ b/src/modules/angular_velocity_controller/CMakeLists.txt @@ -41,6 +41,8 @@ px4_add_module( SRCS AngularVelocityController.cpp AngularVelocityController.hpp + MODULE_CONFIG + module.yaml DEPENDS circuit_breaker mathlib diff --git a/src/modules/angular_velocity_controller/angular_velocity_controller_params.c b/src/modules/angular_velocity_controller/angular_velocity_controller_params.c deleted file mode 100644 index 88c61c400492..000000000000 --- a/src/modules/angular_velocity_controller/angular_velocity_controller_params.c +++ /dev/null @@ -1,297 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file angular_velocity_controller_params.c - * Parameters for angular velocity controller. - * - * @author Lorenz Meier - * @author Anton Babushkin - * @author Julien Lecoeur - */ - -/** - * Body X axis angular velocity P gain - * - * Body X axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. - * - * @unit 1/s - * @min 0.0 - * @max 20.0 - * @decimal 3 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_X_P, 18.f); - -/** - * Body X axis angular velocity I gain - * - * Body X axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. - * - * @unit Nm/rad - * @min 0.0 - * @decimal 3 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_X_I, 0.2f); - -/** - * Body X axis angular velocity integrator limit - * - * Body X axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. - * - * @unit Nm - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_X_I_LIM, 0.3f); - -/** - * Body X axis angular velocity D gain - * - * Body X axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - * - * @min 0.0 - * @max 2.0 - * @decimal 4 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_X_D, 0.36f); - -/** - * Body X axis angular velocity feedforward gain - * - * Improves tracking performance. - * - * @unit Nm/(rad/s) - * @min 0.0 - * @decimal 4 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_X_FF, 0.0f); - -/** - * Body X axis angular velocity controller gain - * - * Global gain of the controller. - * - * This gain scales the P, I and D terms of the controller: - * output = AVC_X_K * (AVC_X_P * error - * + AVC_X_I * error_integral - * + AVC_X_D * error_derivative) - * Set AVC_X_P=1 to implement a PID in the ideal form. - * Set AVC_X_K=1 to implement a PID in the parallel form. - * - * @min 0.0 - * @max 5.0 - * @decimal 4 - * @increment 0.0005 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_X_K, 1.0f); - -/** - * Body Y axis angular velocity P gain - * - * Body Y axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. - * - * @unit 1/s - * @min 0.0 - * @max 20.0 - * @decimal 3 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Y_P, 18.f); - -/** - * Body Y axis angular velocity I gain - * - * Body Y axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. - * - * @unit Nm/rad - * @min 0.0 - * @decimal 3 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Y_I, 0.2f); - -/** - * Body Y axis angular velocity integrator limit - * - * Body Y axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. - * - * @unit Nm - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Y_I_LIM, 0.3f); - -/** - * Body Y axis angular velocity D gain - * - * Body Y axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - * - * @min 0.0 - * @max 2.0 - * @decimal 4 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Y_D, 0.36f); - -/** - * Body Y axis angular velocity feedforward - * - * Improves tracking performance. - * - * @unit Nm/(rad/s) - * @min 0.0 - * @decimal 4 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Y_FF, 0.0f); - -/** - * Body Y axis angular velocity controller gain - * - * Global gain of the controller. - * - * This gain scales the P, I and D terms of the controller: - * output = AVC_Y_K * (AVC_Y_P * error - * + AVC_Y_I * error_integral - * + AVC_Y_D * error_derivative) - * Set AVC_Y_P=1 to implement a PID in the ideal form. - * Set AVC_Y_K=1 to implement a PID in the parallel form. - * - * @min 0.0 - * @max 20.0 - * @decimal 4 - * @increment 0.0005 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Y_K, 1.0f); - -/** - * Body Z axis angular velocity P gain - * - * Body Z axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. - * - * @unit 1/s - * @min 0.0 - * @max 20.0 - * @decimal 2 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Z_P, 7.f); - -/** - * Body Z axis angular velocity I gain - * - * Body Z axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. - * - * @unit Nm/rad - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Z_I, 0.1f); - -/** - * Body Z axis angular velocity integrator limit - * - * Body Z axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. - * - * @unit Nm - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Z_I_LIM, 0.30f); - -/** - * Body Z axis angular velocity D gain - * - * Body Z axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - * - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Z_D, 0.0f); - -/** - * Body Z axis angular velocity feedforward - * - * Improves tracking performance. - * - * @unit Nm/(rad/s) - * @min 0.0 - * @decimal 4 - * @increment 0.01 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Z_FF, 0.0f); - -/** - * Body Z axis angular velocity controller gain - * - * Global gain of the controller. - * - * This gain scales the P, I and D terms of the controller: - * output = AVC_Z_K * (AVC_Z_P * error - * + AVC_Z_I * error_integral - * + AVC_Z_D * error_derivative) - * Set AVC_Z_P=1 to implement a PID in the ideal form. - * Set AVC_Z_K=1 to implement a PID in the parallel form. - * - * @min 0.0 - * @max 5.0 - * @decimal 4 - * @increment 0.0005 - * @group Angular Velocity Control - */ -PARAM_DEFINE_FLOAT(AVC_Z_K, 1.0f); diff --git a/src/modules/angular_velocity_controller/module.yaml b/src/modules/angular_velocity_controller/module.yaml new file mode 100644 index 000000000000..12a55fc3920b --- /dev/null +++ b/src/modules/angular_velocity_controller/module.yaml @@ -0,0 +1,268 @@ +module_name: angular_velocity_controller +parameters: + - definitions: + AVC_X_D: + decimal: 4 + default: 0.36 + description: + long: Body X axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + short: Body X axis angular velocity D gain + increment: 0.01 + max: 2.0 + min: 0.0 + type: float + volatile: false + AVC_X_FF: + decimal: 4 + default: 0.0 + description: + long: Improves tracking performance. + short: Body X axis angular velocity feedforward gain + min: 0.0 + type: float + unit: Nm/(rad/s) + volatile: false + AVC_X_I: + decimal: 3 + default: 0.2 + description: + long: Body X axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. + short: Body X axis angular velocity I gain + increment: 0.01 + min: 0.0 + type: float + unit: Nm/rad + volatile: false + AVC_X_I_LIM: + decimal: 2 + default: 0.3 + description: + long: Body X axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. + short: Body X axis angular velocity integrator limit + increment: 0.01 + min: 0.0 + type: float + unit: Nm + volatile: false + AVC_X_K: + decimal: 4 + default: 1.0 + description: + long: 'Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_X_K * (AVC_X_P * error + AVC_X_I * error_integral + AVC_X_D * error_derivative) Set AVC_X_P=1 to implement a PID in the ideal form. Set AVC_X_K=1 to implement a PID in the parallel form.' + short: Body X axis angular velocity controller gain + increment: 0.0005 + max: 5.0 + min: 0.0 + type: float + volatile: false + AVC_X_P: + decimal: 3 + default: 18.0 + description: + long: Body X axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. + short: Body X axis angular velocity P gain + increment: 0.01 + max: 20.0 + min: 0.0 + type: float + unit: 1/s + volatile: false + AVC_Y_D: + decimal: 4 + default: 0.36 + description: + long: Body Y axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + short: Body Y axis angular velocity D gain + increment: 0.01 + max: 2.0 + min: 0.0 + type: float + volatile: false + AVC_Y_FF: + decimal: 4 + default: 0.0 + description: + long: Improves tracking performance. + short: Body Y axis angular velocity feedforward + min: 0.0 + type: float + unit: Nm/(rad/s) + volatile: false + AVC_Y_I: + decimal: 3 + default: 0.2 + description: + long: Body Y axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. + short: Body Y axis angular velocity I gain + increment: 0.01 + min: 0.0 + type: float + unit: Nm/rad + volatile: false + AVC_Y_I_LIM: + decimal: 2 + default: 0.3 + description: + long: Body Y axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. + short: Body Y axis angular velocity integrator limit + increment: 0.01 + min: 0.0 + type: float + unit: Nm + volatile: false + AVC_Y_K: + decimal: 4 + default: 1.0 + description: + long: 'Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_Y_K * (AVC_Y_P * error + AVC_Y_I * error_integral + AVC_Y_D * error_derivative) Set AVC_Y_P=1 to implement a PID in the ideal form. Set AVC_Y_K=1 to implement a PID in the parallel form.' + short: Body Y axis angular velocity controller gain + increment: 0.0005 + max: 20.0 + min: 0.0 + type: float + volatile: false + AVC_Y_P: + decimal: 3 + default: 18.0 + description: + long: Body Y axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. + short: Body Y axis angular velocity P gain + increment: 0.01 + max: 20.0 + min: 0.0 + type: float + unit: 1/s + volatile: false + AVC_Z_D: + decimal: 2 + default: 0.0 + description: + long: Body Z axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + short: Body Z axis angular velocity D gain + increment: 0.01 + max: 2.0 + min: 0.0 + type: float + volatile: false + AVC_Z_FF: + decimal: 4 + default: 0.0 + description: + long: Improves tracking performance. + short: Body Z axis angular velocity feedforward + increment: 0.01 + min: 0.0 + type: float + unit: Nm/(rad/s) + volatile: false + AVC_Z_I: + decimal: 2 + default: 0.1 + description: + long: Body Z axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. + short: Body Z axis angular velocity I gain + increment: 0.01 + min: 0.0 + type: float + unit: Nm/rad + volatile: false + AVC_Z_I_LIM: + decimal: 2 + default: 0.3 + description: + long: Body Z axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. + short: Body Z axis angular velocity integrator limit + increment: 0.01 + min: 0.0 + type: float + unit: Nm + volatile: false + AVC_Z_K: + decimal: 4 + default: 1.0 + description: + long: 'Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_Z_K * (AVC_Z_P * error + AVC_Z_I * error_integral + AVC_Z_D * error_derivative) Set AVC_Z_P=1 to implement a PID in the ideal form. Set AVC_Z_K=1 to implement a PID in the parallel form.' + short: Body Z axis angular velocity controller gain + increment: 0.0005 + max: 5.0 + min: 0.0 + type: float + volatile: false + AVC_Z_P: + decimal: 2 + default: 7.0 + description: + long: Body Z axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. + short: Body Z axis angular velocity P gain + increment: 0.01 + max: 20.0 + min: 0.0 + type: float + unit: 1/s + volatile: false + group: Angular Velocity Control + - definitions: + VM_INERTIA_XX: + decimal: 5 + default: 0.01 + description: + short: Inertia matrix, XX component + increment: 1.0e-05 + type: float + unit: kg m^2 + volatile: false + VM_INERTIA_XY: + decimal: 5 + default: 0.0 + description: + short: Inertia matrix, XY component + increment: 1.0e-05 + type: float + unit: kg m^2 + volatile: false + VM_INERTIA_XZ: + decimal: 5 + default: 0.0 + description: + short: Inertia matrix, XZ component + increment: 1.0e-05 + type: float + unit: kg m^2 + volatile: false + VM_INERTIA_YY: + decimal: 5 + default: 0.01 + description: + short: Inertia matrix, YY component + increment: 1.0e-05 + type: float + unit: kg m^2 + volatile: false + VM_INERTIA_YZ: + decimal: 5 + default: 0.0 + description: + short: Inertia matrix, YZ component + increment: 1.0e-05 + type: float + unit: kg m^2 + volatile: false + VM_INERTIA_ZZ: + decimal: 5 + default: 0.01 + description: + short: Inertia matrix, ZZ component + increment: 1.0e-05 + type: float + unit: kg m^2 + volatile: false + VM_MASS: + decimal: 5 + default: 1.0 + description: + short: Mass + increment: 1.0e-05 + type: float + unit: kg + volatile: false + group: Vehicle Model diff --git a/src/modules/angular_velocity_controller/vehicle_model_params.c b/src/modules/angular_velocity_controller/vehicle_model_params.c deleted file mode 100644 index a1417791abd8..000000000000 --- a/src/modules/angular_velocity_controller/vehicle_model_params.c +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file vehicle_model_params.c - * Parameters for vehicle model. - * - * @author Julien Lecoeur - */ - -/** - * Mass - * - * @unit kg - * @decimal 5 - * @increment 0.00001 - * @group Vehicle Model - */ -PARAM_DEFINE_FLOAT(VM_MASS, 1.f); - -/** - * Inertia matrix, XX component - * - * @unit kg m^2 - * @decimal 5 - * @increment 0.00001 - * @group Vehicle Model - */ -PARAM_DEFINE_FLOAT(VM_INERTIA_XX, 0.01f); - -/** - * Inertia matrix, YY component - * - * @unit kg m^2 - * @decimal 5 - * @increment 0.00001 - * @group Vehicle Model - */ -PARAM_DEFINE_FLOAT(VM_INERTIA_YY, 0.01f); - -/** - * Inertia matrix, ZZ component - * - * @unit kg m^2 - * @decimal 5 - * @increment 0.00001 - * @group Vehicle Model - */ -PARAM_DEFINE_FLOAT(VM_INERTIA_ZZ, 0.01f); - -/** - * Inertia matrix, XY component - * - * @unit kg m^2 - * @decimal 5 - * @increment 0.00001 - * @group Vehicle Model - */ -PARAM_DEFINE_FLOAT(VM_INERTIA_XY, 0.f); - -/** - * Inertia matrix, XZ component - * - * @unit kg m^2 - * @decimal 5 - * @increment 0.00001 - * @group Vehicle Model - */ -PARAM_DEFINE_FLOAT(VM_INERTIA_XZ, 0.f); - -/** - * Inertia matrix, YZ component - * - * @unit kg m^2 - * @decimal 5 - * @increment 0.00001 - * @group Vehicle Model - */ -PARAM_DEFINE_FLOAT(VM_INERTIA_YZ, 0.f); diff --git a/src/modules/attitude_estimator_q/CMakeLists.txt b/src/modules/attitude_estimator_q/CMakeLists.txt index df9084fe2036..bc468142f903 100644 --- a/src/modules/attitude_estimator_q/CMakeLists.txt +++ b/src/modules/attitude_estimator_q/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( STACK_MAX 1600 SRCS attitude_estimator_q_main.cpp + MODULE_CONFIG + module.yaml DEPENDS world_magnetic_model ) diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c deleted file mode 100644 index 0cea30cda217..000000000000 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c +++ /dev/null @@ -1,136 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* - * @file attitude_estimator_q_params.c - * - * Parameters for attitude estimator (quaternion based) - * - * @author Anton Babushkin - */ - -/** - * Complimentary filter accelerometer weight - * - * @group Attitude Q estimator - * @min 0 - * @max 1 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(ATT_W_ACC, 0.2f); - -/** - * Complimentary filter magnetometer weight - * - * Set to 0 to avoid using the magnetometer. - * - * @group Attitude Q estimator - * @min 0 - * @max 1 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(ATT_W_MAG, 0.1f); - -/** - * Complimentary filter external heading weight - * - * @group Attitude Q estimator - * @min 0 - * @max 1 - */ -PARAM_DEFINE_FLOAT(ATT_W_EXT_HDG, 0.1f); - -/** - * Complimentary filter gyroscope bias weight - * - * @group Attitude Q estimator - * @min 0 - * @max 1 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(ATT_W_GYRO_BIAS, 0.1f); - -/** - * Magnetic declination, in degrees - * - * This parameter is not used in normal operation, - * as the declination is looked up based on the - * GPS coordinates of the vehicle. - * - * @group Attitude Q estimator - * @unit deg - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(ATT_MAG_DECL, 0.0f); - -/** - * Automatic GPS based declination compensation - * - * @group Attitude Q estimator - * @boolean - */ -PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1); - -/** - * External heading usage mode (from Motion capture/Vision) - * - * Set to 1 to use heading estimate from vision. - * Set to 2 to use heading from motion capture. - * - * @group Attitude Q estimator - * @value 0 None - * @value 1 Vision - * @value 2 Motion Capture - * @min 0 - * @max 2 - */ -PARAM_DEFINE_INT32(ATT_EXT_HDG_M, 0); - -/** - * Acceleration compensation based on GPS velocity. - * - * @group Attitude Q estimator - * @boolean - */ -PARAM_DEFINE_INT32(ATT_ACC_COMP, 1); - -/** - * Gyro bias limit - * - * @group Attitude Q estimator - * @unit rad/s - * @min 0 - * @max 2 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(ATT_BIAS_MAX, 0.05f); diff --git a/src/modules/attitude_estimator_q/module.yaml b/src/modules/attitude_estimator_q/module.yaml new file mode 100644 index 000000000000..9d2921a89a11 --- /dev/null +++ b/src/modules/attitude_estimator_q/module.yaml @@ -0,0 +1,84 @@ +module_name: attitude_estimator_q +parameters: + - definitions: + ATT_ACC_COMP: + default: 1 + description: + short: Acceleration compensation based on GPS velocity + type: boolean + volatile: false + ATT_BIAS_MAX: + decimal: 3 + default: 0.05 + description: + short: Gyro bias limit + max: 2 + min: 0 + type: float + unit: rad/s + volatile: false + ATT_EXT_HDG_M: + default: 0 + description: + long: Set to 1 to use heading estimate from vision. Set to 2 to use heading from motion capture. + short: External heading usage mode (from Motion capture/Vision) + max: 2 + min: 0 + type: enum + values: + 0: None + 1: Vision + 2: Motion Capture + volatile: false + ATT_MAG_DECL: + decimal: 2 + default: 0.0 + description: + long: This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle. + short: Magnetic declination, in degrees + type: float + unit: deg + volatile: false + ATT_MAG_DECL_A: + default: 1 + description: + short: Automatic GPS based declination compensation + type: boolean + volatile: false + ATT_W_ACC: + decimal: 2 + default: 0.2 + description: + short: Complimentary filter accelerometer weight + max: 1 + min: 0 + type: float + volatile: false + ATT_W_EXT_HDG: + default: 0.1 + description: + short: Complimentary filter external heading weight + max: 1 + min: 0 + type: float + volatile: false + ATT_W_GYRO_BIAS: + decimal: 2 + default: 0.1 + description: + short: Complimentary filter gyroscope bias weight + max: 1 + min: 0 + type: float + volatile: false + ATT_W_MAG: + decimal: 2 + default: 0.1 + description: + long: Set to 0 to avoid using the magnetometer. + short: Complimentary filter magnetometer weight + max: 1 + min: 0 + type: float + volatile: false + group: Attitude Q estimator diff --git a/src/modules/battery_status/analog_battery_params_common.c b/src/modules/battery_status/analog_battery_params_common.c deleted file mode 100644 index ed33d09c1bfc..000000000000 --- a/src/modules/battery_status/analog_battery_params_common.c +++ /dev/null @@ -1,43 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Offset in volt as seen by the ADC input of the current sensor. - * - * This offset will be subtracted before calculating the battery - * current based on the voltage. - * - * @group Battery Calibration - * @decimal 8 - */ -PARAM_DEFINE_FLOAT(BAT_V_OFFS_CURR, 0.0); diff --git a/src/modules/battery_status/analog_battery_params_deprecated.c b/src/modules/battery_status/analog_battery_params_deprecated.c deleted file mode 100644 index e2a2ade5118c..000000000000 --- a/src/modules/battery_status/analog_battery_params_deprecated.c +++ /dev/null @@ -1,39 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * This parameter is deprecated. Please use BAT1_I_CHANNEL. - * - * @group Battery Calibration - */ -PARAM_DEFINE_INT32(BAT_ADC_CHANNEL, -1); diff --git a/src/modules/battery_status/module.yaml b/src/modules/battery_status/module.yaml index 91359c2947b8..78d910d5120f 100644 --- a/src/modules/battery_status/module.yaml +++ b/src/modules/battery_status/module.yaml @@ -60,4 +60,21 @@ parameters: reboot_required: true num_instances: *max_num_config_instances instance_start: 1 - default: [-1, -1] \ No newline at end of file + default: [-1, -1] + + BAT_ADC_CHANNEL: + description: + short: This parameter is deprecated. Please use BAT1_I_CHANNEL. + + type: int32 + default: -1 + + BAT_V_OFFS_CURR: + description: + short: Offset in volt as seen by the ADC input of the current sensor. + long: | + This offset will be subtracted before calculating the battery current based on the voltage. + + type: float + decimal: 8 + default: 0.0 diff --git a/src/modules/commander/CMakeLists.txt b/src/modules/commander/CMakeLists.txt index 538a79f93f20..b8f1fd265195 100644 --- a/src/modules/commander/CMakeLists.txt +++ b/src/modules/commander/CMakeLists.txt @@ -55,6 +55,8 @@ px4_add_module( Safety.cpp state_machine_helper.cpp worker_thread.cpp + MODULE_CONFIG + module.yaml DEPENDS circuit_breaker failure_detector diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c deleted file mode 100644 index 3daa5ddc690c..000000000000 --- a/src/modules/commander/commander_params.c +++ /dev/null @@ -1,1092 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file commander_params.c - * - * Parameters definition for Commander. - * - * @author Lorenz Meier - * @author Thomas Gubler - * @author Julian Oes - */ - -/** - * Roll trim - * - * The trim value is the actuator control value the system needs - * for straight and level flight. It can be calibrated by - * flying manually straight and level using the RC trims and - * copying them using the GCS. - * - * @group Radio Calibration - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f); - -/** - * Pitch trim - * - * The trim value is the actuator control value the system needs - * for straight and level flight. It can be calibrated by - * flying manually straight and level using the RC trims and - * copying them using the GCS. - * - * @group Radio Calibration - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f); - -/** - * Yaw trim - * - * The trim value is the actuator control value the system needs - * for straight and level flight. It can be calibrated by - * flying manually straight and level using the RC trims and - * copying them using the GCS. - * - * @group Radio Calibration - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f); - -/** - * Datalink loss time threshold - * - * After this amount of seconds without datalink the data link lost mode triggers - * - * @group Commander - * @unit s - * @min 5 - * @max 300 - * @decimal 1 - * @increment 1 - */ -PARAM_DEFINE_INT32(COM_DL_LOSS_T, 10); - -/** - * High Latency Datalink loss time threshold - * - * After this amount of seconds without datalink the data link lost mode triggers - * - * @group Commander - * @unit s - * @min 60 - * @max 3600 - */ -PARAM_DEFINE_INT32(COM_HLDL_LOSS_T, 120); - -/** - * High Latency Datalink regain time threshold - * - * After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss' - * flag is set back to false - * - * @group Commander - * @unit s - * @min 0 - * @max 60 - */ -PARAM_DEFINE_INT32(COM_HLDL_REG_T, 0); - -/** - * RC loss time threshold - * - * After this amount of seconds without RC connection it's considered lost and not used anymore - * - * @group Commander - * @unit s - * @min 0 - * @max 35 - * @decimal 1 - * @increment 0.1 - */ -PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5f); - -/** - * Delay between RC loss and configured reaction - * - * RC signal not updated -> still use data for COM_RC_LOSS_T seconds - * Consider RC signal lost -> wait COM_RCL_ACT_T seconds in Hold mode to regain signal - * React with failsafe action NAV_RCL_ACT - * - * A zero value disables the delay. - * - * @group Commander - * @unit s - * @min 0.0 - * @max 25.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(COM_RCL_ACT_T, 15.0f); - -/** - * Home position enabled - * - * Set home position automatically if possible. - * - * @group Commander - * @reboot_required true - * @boolean - */ -PARAM_DEFINE_INT32(COM_HOME_EN, 1); - -/** - * Allows setting the home position after takeoff - * - * If set to true, the autopilot is allowed to set its home position after takeoff - * The true home position is back-computed if a local position is estimate if available. - * If no local position is available, home is set to the current position. - * - * @boolean - * @group Commander - */ -PARAM_DEFINE_INT32(COM_HOME_IN_AIR, 0); - -/** - * RC control input mode - * - * A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. - * A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. - * A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. - * A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. - * A value of 4 ignores any stick input. - * - * @group Commander - * @min 0 - * @max 4 - * @value 0 RC Transmitter only - * @value 1 Joystick only - * @value 2 RC and Joystick with fallback - * @value 3 RC or Joystick keep first - * @value 4 Stick input disabled - */ -PARAM_DEFINE_INT32(COM_RC_IN_MODE, 3); - -/** - * RC input arm/disarm command duration - * - * The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second. - * - * @group Commander - * @min 100 - * @max 1500 - * @unit ms - */ -PARAM_DEFINE_INT32(COM_RC_ARM_HYST, 1000); - -/** - * Time-out for auto disarm after landing - * - * A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be - * automatically disarmed in case a landing situation has been detected during this period. - * - * A zero or negative value means that automatic disarming triggered by landing detection is disabled. - * - * @group Commander - * @unit s - * @decimal 2 - */ - -PARAM_DEFINE_FLOAT(COM_DISARM_LAND, 2.0f); - -/** - * Time-out for auto disarm if not taking off - * - * A non-zero, positive value specifies the time in seconds, within which the - * vehicle is expected to take off after arming. In case the vehicle didn't takeoff - * within the timeout it disarms again. - * - * A negative value disables autmoatic disarming triggered by a pre-takeoff timeout. - * - * @group Commander - * @unit s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(COM_DISARM_PRFLT, 10.0f); - -/** - * Allow arming without GPS - * - * The default allows the vehicle to arm without GPS signal. - * - * @group Commander - * @value 0 Require GPS lock to arm - * @value 1 Allow arming without GPS - */ -PARAM_DEFINE_INT32(COM_ARM_WO_GPS, 1); - -/** - * Arm switch is a momentary button - * - * 0: Arming/disarming triggers on switch transition. - * 1: Arming/disarming triggers when holding the momentary button down - * for COM_RC_ARM_HYST like the stick gesture. - * - * @group Commander - * @boolean - */ -PARAM_DEFINE_INT32(COM_ARM_SWISBTN, 0); - -/** - * Battery failsafe mode - * - * Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR - * for definition of battery states. - * - * @group Commander - * @value 0 Warning - * @value 2 Land mode - * @value 3 Return at critical level, land at emergency level - * @decimal 0 - * @increment 1 - */ -PARAM_DEFINE_INT32(COM_LOW_BAT_ACT, 0); - -/** - * Delay between battery state change and failsafe reaction - * - * Battery state requires action -> wait COM_BAT_ACT_T seconds in Hold mode - * for the user to realize and take a custom action - * -> React with failsafe action COM_LOW_BAT_ACT - * - * A zero value disables the delay. - * - * @group Commander - * @unit s - * @min 0.0 - * @max 25.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(COM_BAT_ACT_T, 5.f); - -/** - * Imbalanced propeller failsafe mode - * - * Action the system takes when an imbalanced propeller is detected by the failure detector. - * See also FD_IMB_PROP_THR to set the failure threshold. - * - * @group Commander - * - * @value -1 Disabled - * @value 0 Warning - * @value 1 Return - * @value 2 Land - * @decimal 0 - * @increment 1 - */ -PARAM_DEFINE_INT32(COM_IMB_PROP_ACT, 0); - -/** - * Time-out to wait when offboard connection is lost before triggering offboard lost action. - * - * See COM_OBL_ACT and COM_OBL_RC_ACT to configure action. - * - * @group Commander - * @unit s - * @min 0 - * @max 60 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(COM_OF_LOSS_T, 1.0f); - -/** - * Set offboard loss failsafe mode - * - * The offboard loss failsafe will only be entered after a timeout, - * set by COM_OF_LOSS_T in seconds. - * - * @value -1 Disabled - * @value 0 Land mode - * @value 1 Hold mode - * @value 2 Return mode - * @value 3 Terminate - * @value 4 Lockdown - * - * @group Commander - */ -PARAM_DEFINE_INT32(COM_OBL_ACT, 0); - -/** - * Set command after a quadchute - * - * @value -1 No action: stay in current flight mode - * @value 0 Return mode - * @value 1 Land mode - * @value 2 Hold mode - * @group Commander - */ -PARAM_DEFINE_INT32(COM_QC_ACT, 0); - -/** - * Set offboard loss failsafe mode when RC is available - * - * The offboard loss failsafe will only be entered after a timeout, - * set by COM_OF_LOSS_T in seconds. - * - * @value -1 Disabled - * @value 0 Position mode - * @value 1 Altitude mode - * @value 2 Manual - * @value 3 Return mode - * @value 4 Land mode - * @value 5 Hold mode - * @value 6 Terminate - * @value 7 Lockdown - * @group Commander - */ -PARAM_DEFINE_INT32(COM_OBL_RC_ACT, 0); - -/** - * Time-out to wait when onboard computer connection is lost before warning about loss connection. - * - * @group Commander - * @unit s - * @min 0 - * @max 60 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(COM_OBC_LOSS_T, 5.0f); - -/** - * First flightmode slot (1000-1160) - * - * If the main switch channel is in this range the - * selected flight mode will be applied. - * - * @value -1 Unassigned - * @value 0 Manual - * @value 1 Altitude - * @value 2 Position - * @value 3 Mission - * @value 4 Hold - * @value 10 Takeoff - * @value 11 Land - * @value 5 Return - * @value 6 Acro - * @value 7 Offboard - * @value 8 Stabilized - * @value 12 Follow Me - * @value 13 Precision Land - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FLTMODE1, -1); - -/** - * Second flightmode slot (1160-1320) - * - * If the main switch channel is in this range the - * selected flight mode will be applied. - * - * @value -1 Unassigned - * @value 0 Manual - * @value 1 Altitude - * @value 2 Position - * @value 3 Mission - * @value 4 Hold - * @value 10 Takeoff - * @value 11 Land - * @value 5 Return - * @value 6 Acro - * @value 7 Offboard - * @value 8 Stabilized - * @value 12 Follow Me - * @value 13 Precision Land - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FLTMODE2, -1); - -/** - * Third flightmode slot (1320-1480) - * - * If the main switch channel is in this range the - * selected flight mode will be applied. - * - * @value -1 Unassigned - * @value 0 Manual - * @value 1 Altitude - * @value 2 Position - * @value 3 Mission - * @value 4 Hold - * @value 10 Takeoff - * @value 11 Land - * @value 5 Return - * @value 6 Acro - * @value 7 Offboard - * @value 8 Stabilized - * @value 12 Follow Me - * @value 13 Precision Land - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FLTMODE3, -1); - -/** - * Fourth flightmode slot (1480-1640) - * - * If the main switch channel is in this range the - * selected flight mode will be applied. - * - * @value -1 Unassigned - * @value 0 Manual - * @value 1 Altitude - * @value 2 Position - * @value 3 Mission - * @value 4 Hold - * @value 10 Takeoff - * @value 11 Land - * @value 5 Return - * @value 6 Acro - * @value 7 Offboard - * @value 8 Stabilized - * @value 12 Follow Me - * @value 13 Precision Land - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FLTMODE4, -1); - -/** - * Fifth flightmode slot (1640-1800) - * - * If the main switch channel is in this range the - * selected flight mode will be applied. - * - * @value -1 Unassigned - * @value 0 Manual - * @value 1 Altitude - * @value 2 Position - * @value 3 Mission - * @value 4 Hold - * @value 10 Takeoff - * @value 11 Land - * @value 5 Return - * @value 6 Acro - * @value 7 Offboard - * @value 8 Stabilized - * @value 12 Follow Me - * @value 13 Precision Land - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FLTMODE5, -1); - -/** - * Sixth flightmode slot (1800-2000) - * - * If the main switch channel is in this range the - * selected flight mode will be applied. - * - * @value -1 Unassigned - * @value 0 Manual - * @value 1 Altitude - * @value 2 Position - * @value 3 Mission - * @value 4 Hold - * @value 10 Takeoff - * @value 11 Land - * @value 5 Return - * @value 6 Acro - * @value 7 Offboard - * @value 8 Stabilized - * @value 12 Follow Me - * @value 13 Precision Land - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FLTMODE6, -1); - -/** - * Maximum EKF position innovation test ratio that will allow arming - * - * @group Commander - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_POS, 0.5f); - -/** - * Maximum EKF velocity innovation test ratio that will allow arming - * - * @group Commander - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_VEL, 0.5f); - -/** - * Maximum EKF height innovation test ratio that will allow arming - * - * @group Commander - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_HGT, 1.0f); - -/** - * Maximum EKF yaw innovation test ratio that will allow arming - * - * @group Commander - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_YAW, 0.5f); - -/** - * Maximum accelerometer inconsistency between IMU units that will allow arming - * - * @group Commander - * @unit m/s^2 - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_ARM_IMU_ACC, 0.7f); - -/** - * Maximum rate gyro inconsistency between IMU units that will allow arming - * - * @group Commander - * @unit rad/s - * @min 0.02 - * @max 0.3 - * @decimal 3 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(COM_ARM_IMU_GYR, 0.25f); - -/** - * Maximum magnetic field inconsistency between units that will allow arming - * - * Set -1 to disable the check. - * - * @group Commander - * @unit deg - * @min 3 - * @max 180 - */ -PARAM_DEFINE_INT32(COM_ARM_MAG_ANG, 45); - -/** - * Enable mag strength preflight check - * - * Check if the estimator detects a strong magnetic - * disturbance (check enabled by EKF2_MAG_CHECK) - * - * @value 0 Disabled - * @value 1 Deny arming - * @value 2 Warning only - * - * @group Commander - */ -PARAM_DEFINE_INT32(COM_ARM_MAG_STR, 2); - -/** - * Enable RC stick override of auto and/or offboard modes - * - * When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV - * immediately gives control back to the pilot by switching to Position mode and - * if position is unavailable Altitude mode. - * Note: Only has an effect on multicopters, and VTOLs in multicopter mode. - * - * This parameter is not considered in case of a GPS failure (Descend flight mode), where stick - * override is always enabled. - * - * @min 0 - * @max 3 - * @bit 0 Enable override during auto modes (except for in critical battery reaction) - * @bit 1 Enable override during offboard mode - * @group Commander - */ -PARAM_DEFINE_INT32(COM_RC_OVERRIDE, 1); - -/** - * RC stick override threshold - * - * If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold - * the autopilot the pilot takes over control. - * - * @group Commander - * @unit % - * @min 5 - * @max 80 - * @decimal 0 - * @increment 0.05 - */ -PARAM_DEFINE_FLOAT(COM_RC_STICK_OV, 30.0f); - -/** - * Require valid mission to arm - * - * The default allows to arm the vehicle without a valid mission. - * - * @group Commander - * @boolean - */ -PARAM_DEFINE_INT32(COM_ARM_MIS_REQ, 0); - -/** - * Position control navigation loss response. - * - * This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. - * - * @value 0 Altitude/Manual. Assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL. - * @value 1 Land/Terminate. Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION. - * - * @group Commander - */ -PARAM_DEFINE_INT32(COM_POSCTL_NAVL, 0); - -/** - * Require arm authorization to arm - * - * By default off. The default allows to arm the vehicle without a arm authorization. - * - * @group Commander - * @boolean - */ -PARAM_DEFINE_INT32(COM_ARM_AUTH_REQ, 0); - -/** - * Arm authorizer system id - * - * Used if arm authorization is requested by COM_ARM_AUTH_REQ. - * - * @group Commander - */ -PARAM_DEFINE_INT32(COM_ARM_AUTH_ID, 10); - -/** - * Arm authorization method - * - * Methods: - * - one arm: request authorization and arm when authorization is received - * - two step arm: 1st arm command request an authorization and - * 2nd arm command arm the drone if authorized - * - * Used if arm authorization is requested by COM_ARM_AUTH_REQ. - * - * @group Commander - * @value 0 one arm - * @value 1 two step arm - */ -PARAM_DEFINE_INT32(COM_ARM_AUTH_MET, 0); - -/** - * Arm authorization timeout - * - * Timeout for authorizer answer. - * Used if arm authorization is requested by COM_ARM_AUTH_REQ. - * - * @group Commander - * @unit s - * @decimal 1 - * @increment 0.1 - */ -PARAM_DEFINE_FLOAT(COM_ARM_AUTH_TO, 1); - -/** - * Loss of position failsafe activation delay. - * - * This sets number of seconds that the position checks need to be failed before the failsafe will activate. - * The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used. - * - * @unit s - * @group Commander - * @min 1 - * @max 100 - */ -PARAM_DEFINE_INT32(COM_POS_FS_DELAY, 1); - -/** - * Horizontal position error threshold. - * - * This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. - * - * @unit m - * @group Commander - */ -PARAM_DEFINE_FLOAT(COM_POS_FS_EPH, 5); - -/** - * Vertical position error threshold. - * - * This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. - * - * @unit m - * @group Commander - */ -PARAM_DEFINE_FLOAT(COM_POS_FS_EPV, 10); - -/** - * Horizontal velocity error threshold. - * - * This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. - * - * @unit m/s - * @group Commander - */ -PARAM_DEFINE_FLOAT(COM_VEL_FS_EVH, 1); - -/** - * Next flight UUID - * - * This number is incremented automatically after every flight on - * disarming in order to remember the next flight UUID. - * The first flight is 0. - * - * @group Commander - * @category system - * @volatile - * @min 0 - */ -PARAM_DEFINE_INT32(COM_FLIGHT_UUID, 0); - -/** - * Action after TAKEOFF has been accepted. - * - * The mode transition after TAKEOFF has completed successfully. - * - * @value 0 Hold - * @value 1 Mission (if valid) - * @group Commander - */ -PARAM_DEFINE_INT32(COM_TAKEOFF_ACT, 0); - -/** - * Set data link loss failsafe mode - * - * The data link loss failsafe will only be entered after a timeout, - * set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected - * action will be executed. - * - * @value 0 Disabled - * @value 1 Hold mode - * @value 2 Return mode - * @value 3 Land mode - * @value 5 Terminate - * @value 6 Lockdown - * @min 0 - * @max 6 - * - * @group Commander - */ -PARAM_DEFINE_INT32(NAV_DLL_ACT, 0); - -/** - * Set RC loss failsafe mode - * - * The RC loss failsafe will only be entered after a timeout, - * set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled - * by setting the COM_RC_IN_MODE param it will not be triggered. - * - * @value 1 Hold mode - * @value 2 Return mode - * @value 3 Land mode - * @value 5 Terminate - * @value 6 Lockdown - * @min 1 - * @max 6 - * - * @group Commander - */ -PARAM_DEFINE_INT32(NAV_RCL_ACT, 2); - -/** - * RC loss exceptions - * - * Specify modes in which RC loss is ignored and the failsafe action not triggered. - * - * @min 0 - * @max 31 - * @bit 0 Mission - * @bit 1 Hold - * @bit 2 Offboard - * @group Commander - */ -PARAM_DEFINE_INT32(COM_RCL_EXCEPT, 0); - -/** - * Set the actuator failure failsafe mode - * - * Note: actuator failure needs to be enabled and configured via FD_ACT_* - * parameters. - * - * @min 0 - * @max 3 - * @value 0 Disabled - * @value 1 Hold mode - * @value 2 Land mode - * @value 3 Return mode - * @value 4 Terminate - * @group Commander - */ -PARAM_DEFINE_INT32(COM_ACT_FAIL_ACT, 0); - -/** - * Flag to enable obstacle avoidance. - * - * @boolean - * @group Commander - */ -PARAM_DEFINE_INT32(COM_OBS_AVOID, 0); - -/** - * Expect and require a healthy MAVLink parachute system - * - * @boolean - * @group Commander - */ -PARAM_DEFINE_INT32(COM_PARACHUTE, 0); - -/** - * User Flight Profile - * - * Describes the intended use of the vehicle. - * Can be used by ground control software or log post processing. - * This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params). - * - * @value 0 Default - * @value 100 Pro User - * @value 200 Flight Tester - * @value 300 Developer - * - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FLT_PROFILE, 0); - -/** - * Enable checks on ESCs that report telemetry. - * - * If this parameter is set, the system will check ESC's online status and failures. - * This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry. - * - * @group Commander - * @boolean - */ -PARAM_DEFINE_INT32(COM_ARM_CHK_ESCS, 0); - -/** - * Condition to enter prearmed mode - * - * Condition to enter the prearmed state, an intermediate state between disarmed and armed - * in which non-throttling actuators are active. - * - * @value 0 Disabled - * @value 1 Safety button - * @value 2 Always - * - * @group Commander - */ -PARAM_DEFINE_INT32(COM_PREARM_MODE, 0); - -/** - * Enable force safety - * - * Force safety when the vehicle disarms - * - * @boolean - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FORCE_SAFETY, 0); - -/** - * Enable Motor Testing - * - * If set, enables the motor test interface via MAVLink (DO_MOTOR_TEST), that - * allows spinning the motors for testing purposes. - * - * @boolean - * @group Commander - */ -PARAM_DEFINE_INT32(COM_MOT_TEST_EN, 1); - -/** - * Timeout value for disarming when kill switch is engaged - * - * @group Commander - * @unit s - * @min 0.0 - * @max 30.0 - * @increment 0.1 - */ -PARAM_DEFINE_FLOAT(COM_KILL_DISARM, 5.0f); - -/** - * Maximum allowed CPU load to still arm - * - * A negative value disables the check. - * - * @group Commander - * @unit % - * @min -1 - * @max 100 - * @increment 1 - */ -PARAM_DEFINE_FLOAT(COM_CPU_MAX, 90.0f); - -/** - * Required number of redundant power modules - * - * This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. - * Note: CBRK_SUPPLY_CHK disables all power checks including this one. - * - * @group Commander - * @min 0 - * @max 4 - */ -PARAM_DEFINE_INT32(COM_POWER_COUNT, 1); - -/** - * Timeout for detecting a failure after takeoff - * - * A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to put the vehicle into - * a lockdown state if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. - * The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). - * A zero or negative value means that the check is disabled. - * - * @group Commander - * @unit s - * @min -1.0 - * @max 5.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(COM_LKDOWN_TKO, 3.0f); - -/** -* Enable preflight check for maximal allowed airspeed when arming. -* -* Deny arming if the current airspeed measurement is greater than half the cruise airspeed (FW_AIRSPD_TRIM). -* Excessive airspeed measurements on ground are either caused by wind or bad airspeed calibration. -* -* @group Commander -* @value 0 Disabled -* @value 1 Enabled -*/ -PARAM_DEFINE_INT32(COM_ARM_ARSP_EN, 1); - -/** - * Enable FMU SD card detection check - * - * This check detects if the FMU SD card is missing. - * Depending on the value of the parameter, the check can be - * disabled, warn only or deny arming. - * - * @group Commander - * @value 0 Disabled - * @value 1 Warning only - * @value 2 Enforce SD card presence - */ -PARAM_DEFINE_INT32(COM_ARM_SDCARD, 1); - -/** - * Enforced delay between arming and further navigation - * - * The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. - * Goal: - * - Motors and propellers spool up to idle speed before getting commanded to spin faster - * - Timeout for ESCs and smart batteries to successfulyy do failure checks - * e.g. for stuck rotors before the vehicle is off the ground - * - * @group Commander - * @min 0 - * @max 5 - * @unit s - */ -PARAM_DEFINE_FLOAT(COM_SPOOLUP_TIME, 1.0f); - -/** - * Wind speed warning threshold - * - * A warning is triggered if the currently estimated wind speed is above this value. - * Warning is sent periodically (every 1min). - * - * A negative value disables the feature. - * - * @min -1 - * @max 30 - * @decimal 1 - * @increment 0.1 - * @group Commander - * @unit m/s - */ -PARAM_DEFINE_FLOAT(COM_WIND_WARN, -1.f); - -/** - * Maximum allowed flight time - * - * The vehicle aborts the current operation and returns to launch when - * the time since takeoff is above this value. It is not possible to resume the - * mission or switch to any mode other than RTL or Land. - * - * Set a nagative value to disable. - * - * - * @unit s - * @min -1 - * @max 10000 - * @value 0 Disable - * @group Commander - */ -PARAM_DEFINE_INT32(COM_FLT_TIME_MAX, -1); - -/** - * Wind speed RLT threshold - * - * Wind speed threshold above which an automatic return to launch is triggered - * and enforced as long as the threshold is exceeded. - * - * A negative value disables the feature. - * - * @min -1 - * @max 30 - * @decimal 1 - * @increment 0.1 - * @group Commander - * @unit m/s - */ -PARAM_DEFINE_FLOAT(COM_WIND_MAX, -1.f); diff --git a/src/modules/commander/failure_detector/failure_detector_params.c b/src/modules/commander/failure_detector/failure_detector_params.c deleted file mode 100644 index e472c304b86f..000000000000 --- a/src/modules/commander/failure_detector/failure_detector_params.c +++ /dev/null @@ -1,214 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file failure_detector_params.c - * - * Parameters used by the Failure Detector. - * - * @author Mathieu Bresciani - */ - -#include -#include - -/** - * FailureDetector Max Roll - * - * Maximum roll angle before FailureDetector triggers the attitude_failure flag. - * The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), - * which sets outputs to their failsafe values. - * On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), - * which disarms motors but does not set outputs to failsafe values. - * - * Setting this parameter to 0 disables the check - * - * @min 0 - * @max 180 - * @unit deg - * @group Failure Detector - */ -PARAM_DEFINE_INT32(FD_FAIL_R, 60); - -/** - * FailureDetector Max Pitch - * - * Maximum pitch angle before FailureDetector triggers the attitude_failure flag. - * The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), - * which sets outputs to their failsafe values. - * On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), - * which disarms motors but does not set outputs to failsafe values. - * - * Setting this parameter to 0 disables the check - * - * @min 0 - * @max 180 - * @unit deg - * @group Failure Detector - */ -PARAM_DEFINE_INT32(FD_FAIL_P, 60); - -/** - * Roll failure trigger time - * - * Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure. - * - * @unit s - * @min 0.02 - * @max 5 - * @decimal 2 - * - * @group Failure Detector - */ -PARAM_DEFINE_FLOAT(FD_FAIL_R_TTRI, 0.3); - -/** - * Pitch failure trigger time - * - * Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure. - * - * @unit s - * @min 0.02 - * @max 5 - * @decimal 2 - * - * @group Failure Detector - */ -PARAM_DEFINE_FLOAT(FD_FAIL_P_TTRI, 0.3); - -/** - * Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS). - * - * Enabled on either AUX5 or MAIN5 depending on board. - * External ATS is required by ASTM F3322-18. - * - * @boolean - * @reboot_required true - * @group Failure Detector - */ -PARAM_DEFINE_INT32(FD_EXT_ATS_EN, 0); - -/** - * The PWM threshold from external automatic trigger system for engaging failsafe. - * - * External ATS is required by ASTM F3322-18. - * - * @unit us - * @decimal 2 - * - * @group Failure Detector - */ -PARAM_DEFINE_INT32(FD_EXT_ATS_TRIG, 1900); - -/** - * Enable checks on ESCs that report their arming state. - * - * If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. - * Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle. - * - * @boolean - * - * @group Failure Detector - */ -PARAM_DEFINE_INT32(FD_ESCS_EN, 1); - -/** - * Imbalanced propeller check threshold - * - * Value at which the imbalanced propeller metric (based on horizontal and - * vertical acceleration variance) triggers a failure - * - * Setting this value to 0 disables the feature. - * - * @min 0 - * @max 1000 - * @increment 1 - * @group Failure Detector - */ -PARAM_DEFINE_INT32(FD_IMB_PROP_THR, 30); - -/** - * Enable Actuator Failure check - * - * If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle - * level is being consumed. - * Otherwise this indicates an motor failure. - * - * @boolean - * @reboot_required true - * - * @group Failure Detector - */ -PARAM_DEFINE_INT32(FD_ACT_EN, 1); - -/** - * Motor Failure Throttle Threshold - * - * Motor failure triggers only above this throttle value. - * - * @group Failure Detector - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FD_ACT_MOT_THR, 0.2f); - -/** - * Motor Failure Current/Throttle Threshold - * - * Motor failure triggers only below this current value - * - * @group Failure Detector - * @min 0.0 - * @max 50.0 - * @unit A/% - * @decimal 2 - * @increment 1 - */ -PARAM_DEFINE_FLOAT(FD_ACT_MOT_C2T, 2.0f); - -/** - * Motor Failure Time Threshold - * - * Motor failure triggers only if the throttle threshold and the - * current to throttle threshold are violated for this time. - * - * @group Failure Detector - * @unit ms - * @min 10 - * @max 10000 - * @increment 100 - */ -PARAM_DEFINE_INT32(FD_ACT_MOT_TOUT, 100); diff --git a/src/modules/commander/module.yaml b/src/modules/commander/module.yaml new file mode 100644 index 000000000000..9ad6f49b8bc9 --- /dev/null +++ b/src/modules/commander/module.yaml @@ -0,0 +1,957 @@ +module_name: commander +parameters: + - definitions: + COM_ACT_FAIL_ACT: + default: 0 + description: + long: 'Note: actuator failure needs to be enabled and configured via FD_ACT_* parameters.' + short: Set the actuator failure failsafe mode + max: 3 + min: 0 + type: enum + values: + 0: Disabled + 1: Hold mode + 2: Land mode + 3: Return mode + 4: Terminate + volatile: false + COM_ARM_ARSP_EN: + default: 1 + description: + long: Deny arming if the current airspeed measurement is greater than half the cruise airspeed (FW_AIRSPD_TRIM). Excessive airspeed measurements on ground are either caused by wind or bad airspeed calibration. + short: Enable preflight check for maximal allowed airspeed when arming + type: enum + values: + 0: Disabled + 1: Enabled + volatile: false + COM_ARM_AUTH_ID: + default: 10 + description: + long: Used if arm authorization is requested by COM_ARM_AUTH_REQ. + short: Arm authorizer system id + type: int32 + volatile: false + COM_ARM_AUTH_MET: + default: 0 + description: + long: 'Methods: - one arm: request authorization and arm when authorization is received - two step arm: 1st arm command request an authorization and 2nd arm command arm the drone if authorized Used if arm authorization is requested by COM_ARM_AUTH_REQ.' + short: Arm authorization method + type: enum + values: + 0: one arm + 1: two step arm + volatile: false + COM_ARM_AUTH_REQ: + default: 0 + description: + long: By default off. The default allows to arm the vehicle without a arm authorization. + short: Require arm authorization to arm + type: boolean + volatile: false + COM_ARM_AUTH_TO: + decimal: 1 + default: 1 + description: + long: Timeout for authorizer answer. Used if arm authorization is requested by COM_ARM_AUTH_REQ. + short: Arm authorization timeout + increment: 0.1 + type: float + unit: s + volatile: false + COM_ARM_CHK_ESCS: + default: 0 + description: + long: If this parameter is set, the system will check ESC's online status and failures. This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry. + short: Enable checks on ESCs that report telemetry + type: boolean + volatile: false + COM_ARM_EKF_HGT: + decimal: 2 + default: 1.0 + description: + short: Maximum EKF height innovation test ratio that will allow arming + increment: 0.05 + max: 1.0 + min: 0.1 + type: float + volatile: false + COM_ARM_EKF_POS: + decimal: 2 + default: 0.5 + description: + short: Maximum EKF position innovation test ratio that will allow arming + increment: 0.05 + max: 1.0 + min: 0.1 + type: float + volatile: false + COM_ARM_EKF_VEL: + decimal: 2 + default: 0.5 + description: + short: Maximum EKF velocity innovation test ratio that will allow arming + increment: 0.05 + max: 1.0 + min: 0.1 + type: float + volatile: false + COM_ARM_EKF_YAW: + decimal: 2 + default: 0.5 + description: + short: Maximum EKF yaw innovation test ratio that will allow arming + increment: 0.05 + max: 1.0 + min: 0.1 + type: float + volatile: false + COM_ARM_IMU_ACC: + decimal: 2 + default: 0.7 + description: + short: Max accel inconsistency between IMU units that will allow arming + increment: 0.05 + max: 1.0 + min: 0.1 + type: float + unit: m/s^2 + volatile: false + COM_ARM_IMU_GYR: + decimal: 3 + default: 0.25 + description: + short: Max rate gyro inconsistency between IMU units that will allow arming + increment: 0.01 + max: 0.3 + min: 0.02 + type: float + unit: rad/s + volatile: false + COM_ARM_MAG_ANG: + default: 45 + description: + long: Set -1 to disable the check. + short: Max magnetic field inconsistency between units that will allow arming + max: 180 + min: 3 + type: int32 + unit: deg + volatile: false + COM_ARM_MAG_STR: + default: 2 + description: + long: Check if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK) + short: Enable mag strength preflight check + type: enum + values: + 0: Disabled + 1: Deny arming + 2: Warning only + volatile: false + COM_ARM_MIS_REQ: + default: 0 + description: + long: The default allows to arm the vehicle without a valid mission. + short: Require valid mission to arm + type: boolean + volatile: false + COM_ARM_SDCARD: + default: 1 + description: + long: This check detects if the FMU SD card is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming. + short: Enable FMU SD card detection check + type: enum + values: + 0: Disabled + 1: Warning only + 2: Enforce SD card presence + volatile: false + COM_ARM_SWISBTN: + default: 0 + description: + long: '0: Arming/disarming triggers on switch transition. 1: Arming/disarming triggers when holding the momentary button down for COM_RC_ARM_HYST like the stick gesture.' + short: Arm switch is a momentary button + type: boolean + volatile: false + COM_ARM_WO_GPS: + default: 1 + description: + long: The default allows the vehicle to arm without GPS signal. + short: Allow arming without GPS + type: enum + values: + 0: Require GPS lock to arm + 1: Allow arming without GPS + volatile: false + COM_BAT_ACT_T: + decimal: 3 + default: 5.0 + description: + long: Battery state requires action -> wait COM_BAT_ACT_T seconds in Hold mode for the user to realize and take a custom action -> React with failsafe action COM_LOW_BAT_ACT A zero value disables the delay. + short: Delay between battery state change and failsafe reaction + max: 25.0 + min: 0.0 + type: float + unit: s + volatile: false + COM_CPU_MAX: + default: 90.0 + description: + long: A negative value disables the check. + short: Maximum allowed CPU load to still arm + increment: 1 + max: 100 + min: -1 + type: float + unit: '%' + volatile: false + COM_DISARM_LAND: + decimal: 2 + default: 2.0 + description: + long: A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled. + short: Time-out for auto disarm after landing + type: float + unit: s + volatile: false + COM_DISARM_PRFLT: + decimal: 2 + default: 10.0 + description: + long: A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout. + short: Time-out for auto disarm if not taking off + type: float + unit: s + volatile: false + COM_DL_LOSS_T: + decimal: 1 + default: 10 + description: + long: After this amount of seconds without datalink the data link lost mode triggers + short: Datalink loss time threshold + increment: 1 + max: 300 + min: 5 + type: int32 + unit: s + volatile: false + COM_FLIGHT_UUID: + category: System + default: 0 + description: + long: This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0. + short: Next flight UUID + min: 0 + type: int32 + volatile: true + COM_FLTMODE1: + default: -1 + description: + long: If the main switch channel is in this range the selected flight mode will be applied. + short: First flightmode slot (1000-1160) + type: enum + values: + -1: Unassigned + 0: Manual + 1: Altitude + 2: Position + 3: Mission + 4: Hold + 5: Return + 6: Acro + 7: Offboard + 8: Stabilized + 10: Takeoff + 11: Land + 12: Follow Me + 13: Precision Land + volatile: false + COM_FLTMODE2: + default: -1 + description: + long: If the main switch channel is in this range the selected flight mode will be applied. + short: Second flightmode slot (1160-1320) + type: enum + values: + -1: Unassigned + 0: Manual + 1: Altitude + 2: Position + 3: Mission + 4: Hold + 5: Return + 6: Acro + 7: Offboard + 8: Stabilized + 10: Takeoff + 11: Land + 12: Follow Me + 13: Precision Land + volatile: false + COM_FLTMODE3: + default: -1 + description: + long: If the main switch channel is in this range the selected flight mode will be applied. + short: Third flightmode slot (1320-1480) + type: enum + values: + -1: Unassigned + 0: Manual + 1: Altitude + 2: Position + 3: Mission + 4: Hold + 5: Return + 6: Acro + 7: Offboard + 8: Stabilized + 10: Takeoff + 11: Land + 12: Follow Me + 13: Precision Land + volatile: false + COM_FLTMODE4: + default: -1 + description: + long: If the main switch channel is in this range the selected flight mode will be applied. + short: Fourth flightmode slot (1480-1640) + type: enum + values: + -1: Unassigned + 0: Manual + 1: Altitude + 2: Position + 3: Mission + 4: Hold + 5: Return + 6: Acro + 7: Offboard + 8: Stabilized + 10: Takeoff + 11: Land + 12: Follow Me + 13: Precision Land + volatile: false + COM_FLTMODE5: + default: -1 + description: + long: If the main switch channel is in this range the selected flight mode will be applied. + short: Fifth flightmode slot (1640-1800) + type: enum + values: + -1: Unassigned + 0: Manual + 1: Altitude + 2: Position + 3: Mission + 4: Hold + 5: Return + 6: Acro + 7: Offboard + 8: Stabilized + 10: Takeoff + 11: Land + 12: Follow Me + 13: Precision Land + volatile: false + COM_FLTMODE6: + default: -1 + description: + long: If the main switch channel is in this range the selected flight mode will be applied. + short: Sixth flightmode slot (1800-2000) + type: enum + values: + -1: Unassigned + 0: Manual + 1: Altitude + 2: Position + 3: Mission + 4: Hold + 5: Return + 6: Acro + 7: Offboard + 8: Stabilized + 10: Takeoff + 11: Land + 12: Follow Me + 13: Precision Land + volatile: false + COM_FLT_PROFILE: + default: 0 + description: + long: Describes the intended use of the vehicle. Can be used by ground control software or log post processing. This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params). + short: User Flight Profile + type: enum + values: + 0: Default + 100: Pro User + 200: Flight Tester + 300: Developer + volatile: false + COM_FLT_TIME_MAX: + default: -1 + description: + long: The vehicle aborts the current operation and returns to launch when the time since takeoff is above this value. It is not possible to resume the mission or switch to any mode other than RTL or Land. Set a nagative value to disable. + short: Maximum allowed flight time + max: 10000 + min: -1 + type: enum + unit: s + values: + 0: Disable + volatile: false + COM_FORCE_SAFETY: + default: 0 + description: + long: Force safety when the vehicle disarms + short: Enable force safety + type: boolean + volatile: false + COM_HLDL_LOSS_T: + default: 120 + description: + long: After this amount of seconds without datalink the data link lost mode triggers + short: High Latency Datalink loss time threshold + max: 3600 + min: 60 + type: int32 + unit: s + volatile: false + COM_HLDL_REG_T: + default: 0 + description: + long: 'After a data link loss: after this number of seconds with a healthy datalink the ''datalink loss'' flag is set back to false' + short: High Latency Datalink regain time threshold + max: 60 + min: 0 + type: int32 + unit: s + volatile: false + COM_HOME_EN: + default: 1 + description: + long: Set home position automatically if possible. + short: Home position enabled + reboot_required: true + type: boolean + volatile: false + COM_HOME_IN_AIR: + default: 0 + description: + long: If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position. + short: Allows setting the home position after takeoff + type: boolean + volatile: false + COM_IMB_PROP_ACT: + decimal: 0 + default: 0 + description: + long: Action the system takes when an imbalanced propeller is detected by the failure detector. See also FD_IMB_PROP_THR to set the failure threshold. + short: Imbalanced propeller failsafe mode + increment: 1 + type: enum + values: + -1: Disabled + 0: Warning + 1: Return + 2: Land + volatile: false + COM_KILL_DISARM: + default: 5.0 + description: + short: Timeout value for disarming when kill switch is engaged + increment: 0.1 + max: 30.0 + min: 0.0 + type: float + unit: s + volatile: false + COM_LKDOWN_TKO: + decimal: 3 + default: 3.0 + description: + long: 'A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to put the vehicle into a lockdown state if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled.' + short: Timeout for detecting a failure after takeoff + max: 5.0 + min: -1.0 + type: float + unit: s + volatile: false + COM_LOW_BAT_ACT: + decimal: 0 + default: 0 + description: + long: Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR for definition of battery states. + short: Battery failsafe mode + increment: 1 + type: enum + values: + 0: Warning + 2: Land mode + 3: Return at critical level, land at emergency level + volatile: false + COM_MOT_TEST_EN: + default: 1 + description: + long: If set, enables the motor test interface via MAVLink (DO_MOTOR_TEST), that allows spinning the motors for testing purposes. + short: Enable Motor Testing + type: boolean + volatile: false + COM_OBC_LOSS_T: + default: 5.0 + description: + short: Timeout when onboard computer connection is lost before warning + increment: 0.01 + max: 60 + min: 0 + type: float + unit: s + volatile: false + COM_OBL_ACT: + default: 0 + description: + long: The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. + short: Set offboard loss failsafe mode + type: enum + values: + -1: Disabled + 0: Land mode + 1: Hold mode + 2: Return mode + 3: Terminate + 4: Lockdown + volatile: false + COM_OBL_RC_ACT: + default: 0 + description: + long: The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. + short: Set offboard loss failsafe mode when RC is available + type: enum + values: + -1: Disabled + 0: Position mode + 1: Altitude mode + 2: Manual + 3: Return mode + 4: Land mode + 5: Hold mode + 6: Terminate + 7: Lockdown + volatile: false + COM_OBS_AVOID: + default: 0 + description: + short: Flag to enable obstacle avoidance + type: boolean + volatile: false + COM_OF_LOSS_T: + default: 1.0 + description: + long: See COM_OBL_ACT and COM_OBL_RC_ACT to configure action. + short: Timeout when offboard connection is lost before triggering + increment: 0.01 + max: 60 + min: 0 + type: float + unit: s + volatile: false + COM_PARACHUTE: + default: 0 + description: + short: Expect and require a healthy MAVLink parachute system + type: boolean + volatile: false + COM_POSCTL_NAVL: + default: 0 + description: + long: This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. + short: Position control navigation loss response + type: enum + values: + 0: Altitude/Manual. Assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL. + 1: Land/Terminate. Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION. + volatile: false + COM_POS_FS_DELAY: + default: 1 + description: + long: This sets number of seconds that the position checks need to be failed before the failsafe will activate. The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used. + short: Loss of position failsafe activation delay + max: 100 + min: 1 + type: int32 + unit: s + volatile: false + COM_POS_FS_EPH: + default: 5 + description: + long: This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + short: Horizontal position error threshold + type: float + unit: m + volatile: false + COM_POS_FS_EPV: + default: 10 + description: + long: This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + short: Vertical position error threshold + type: float + unit: m + volatile: false + COM_POWER_COUNT: + default: 1 + description: + long: 'This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one.' + short: Required number of redundant power modules + max: 4 + min: 0 + type: int32 + volatile: false + COM_PREARM_MODE: + default: 0 + description: + long: Condition to enter the prearmed state, an intermediate state between disarmed and armed in which non-throttling actuators are active. + short: Condition to enter prearmed mode + type: enum + values: + 0: Disabled + 1: Safety button + 2: Always + volatile: false + COM_QC_ACT: + default: 0 + description: + short: Set command after a quadchute + type: enum + values: + -1: 'No action: stay in current flight mode' + 0: Return mode + 1: Land mode + 2: Hold mode + volatile: false + COM_RCL_ACT_T: + decimal: 3 + default: 15.0 + description: + long: RC signal not updated -> still use data for COM_RC_LOSS_T seconds Consider RC signal lost -> wait COM_RCL_ACT_T seconds in Hold mode to regain signal React with failsafe action NAV_RCL_ACT A zero value disables the delay. + short: Delay between RC loss and configured reaction + max: 25.0 + min: 0.0 + type: float + unit: s + volatile: false + COM_RCL_EXCEPT: + bit: + 0: Mission + 1: Hold + 2: Offboard + default: 0 + description: + long: Specify modes in which RC loss is ignored and the failsafe action not triggered. + short: RC loss exceptions + max: 31 + min: 0 + type: bitmask + volatile: false + COM_RC_ARM_HYST: + default: 1000 + description: + long: The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second. + short: RC input arm/disarm command duration + max: 1500 + min: 100 + type: int32 + unit: ms + volatile: false + COM_RC_IN_MODE: + default: 3 + description: + long: A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. A value of 4 ignores any stick input. + short: RC control input mode + max: 4 + min: 0 + type: enum + values: + 0: RC Transmitter only + 1: Joystick only + 2: RC and Joystick with fallback + 3: RC or Joystick keep first + 4: Stick input disabled + volatile: false + COM_RC_LOSS_T: + decimal: 1 + default: 0.5 + description: + long: After this amount of seconds without RC connection it's considered lost and not used anymore + short: RC loss time threshold + increment: 0.1 + max: 35 + min: 0 + type: float + unit: s + volatile: false + COM_RC_OVERRIDE: + bit: + 0: Enable override during auto modes (except for in critical battery reaction) + 1: Enable override during offboard mode + default: 1 + description: + long: 'When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode. This parameter is not considered in case of a GPS failure (Descend flight mode), where stick override is always enabled.' + short: Enable RC stick override of auto and/or offboard modes + max: 3 + min: 0 + type: bitmask + volatile: false + COM_RC_STICK_OV: + decimal: 0 + default: 30.0 + description: + long: If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold the autopilot the pilot takes over control. + short: RC stick override threshold + increment: 0.05 + max: 80 + min: 5 + type: float + unit: '%' + volatile: false + COM_SPOOLUP_TIME: + default: 1.0 + description: + long: 'The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. Goal: - Motors and propellers spool up to idle speed before getting commanded to spin faster - Timeout for ESCs and smart batteries to successfulyy do failure checks e.g. for stuck rotors before the vehicle is off the ground' + short: Enforced delay between arming and further navigation + max: 5 + min: 0 + type: float + unit: s + volatile: false + COM_TAKEOFF_ACT: + default: 0 + description: + long: The mode transition after TAKEOFF has completed successfully. + short: Action after TAKEOFF has been accepted + type: enum + values: + 0: Hold + 1: Mission (if valid) + volatile: false + COM_VEL_FS_EVH: + default: 1 + description: + long: This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + short: Horizontal velocity error threshold + type: float + unit: m/s + volatile: false + COM_WIND_MAX: + decimal: 1 + default: -1.0 + description: + long: Wind speed threshold above which an automatic return to launch is triggered and enforced as long as the threshold is exceeded. A negative value disables the feature. + short: Wind speed RLT threshold + increment: 0.1 + max: 30 + min: -1 + type: float + unit: m/s + volatile: false + COM_WIND_WARN: + decimal: 1 + default: -1.0 + description: + long: A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1min). A negative value disables the feature. + short: Wind speed warning threshold + increment: 0.1 + max: 30 + min: -1 + type: float + unit: m/s + volatile: false + NAV_DLL_ACT: + default: 0 + description: + long: The data link loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. + short: Set data link loss failsafe mode + max: 6 + min: 0 + type: enum + values: + 0: Disabled + 1: Hold mode + 2: Return mode + 3: Land mode + 5: Terminate + 6: Lockdown + volatile: false + NAV_RCL_ACT: + default: 2 + description: + long: The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered. + short: Set RC loss failsafe mode + max: 6 + min: 1 + type: enum + values: + 1: Hold mode + 2: Return mode + 3: Land mode + 5: Terminate + 6: Lockdown + volatile: false + group: Commander + - definitions: + TRIM_PITCH: + decimal: 2 + default: 0.0 + description: + long: The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + short: Pitch trim + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + TRIM_ROLL: + decimal: 2 + default: 0.0 + description: + long: The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + short: Roll trim + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + TRIM_YAW: + decimal: 2 + default: 0.0 + description: + long: The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + short: Yaw trim + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + group: Radio Calibration + - definitions: + FD_ACT_EN: + default: 1 + description: + long: If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle level is being consumed. Otherwise this indicates an motor failure. + short: Enable Actuator Failure check + reboot_required: true + type: boolean + volatile: false + FD_ACT_MOT_C2T: + decimal: 2 + default: 2.0 + description: + long: Motor failure triggers only below this current value + short: Motor Failure Current/Throttle Threshold + increment: 1 + max: 50.0 + min: 0.0 + type: float + unit: A/% + volatile: false + FD_ACT_MOT_THR: + decimal: 2 + default: 0.2 + description: + long: Motor failure triggers only above this throttle value. + short: Motor Failure Throttle Threshold + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FD_ACT_MOT_TOUT: + default: 100 + description: + long: Motor failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time. + short: Motor Failure Time Threshold + increment: 100 + max: 10000 + min: 10 + type: int32 + unit: ms + volatile: false + FD_ESCS_EN: + default: 1 + description: + long: If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle. + short: Enable checks on ESCs that report their arming state + type: boolean + volatile: false + FD_EXT_ATS_EN: + default: 0 + description: + long: Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18. + short: Enable PWM input on for engaging failsafe from external trigger system + reboot_required: true + type: boolean + volatile: false + FD_EXT_ATS_TRIG: + decimal: 2 + default: 1900 + description: + long: External ATS is required by ASTM F3322-18. + short: PWM threshold from external trigger system to engage failsafe + type: int32 + unit: us + volatile: false + FD_FAIL_P: + default: 60 + description: + long: Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check + short: FailureDetector Max Pitch + max: 180 + min: 0 + type: int32 + unit: deg + volatile: false + FD_FAIL_P_TTRI: + decimal: 2 + default: 0.3 + description: + long: Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure. + short: Pitch failure trigger time + max: 5 + min: 0.02 + type: float + unit: s + volatile: false + FD_FAIL_R: + default: 60 + description: + long: Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check + short: FailureDetector Max Roll + max: 180 + min: 0 + type: int32 + unit: deg + volatile: false + FD_FAIL_R_TTRI: + decimal: 2 + default: 0.3 + description: + long: Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure. + short: Roll failure trigger time + max: 5 + min: 0.02 + type: float + unit: s + volatile: false + FD_IMB_PROP_THR: + default: 30 + description: + long: Value at which the imbalanced propeller metric (based on horizontal and vertical acceleration variance) triggers a failure Setting this value to 0 disables the feature. + short: Imbalanced propeller check threshold + increment: 1 + max: 1000 + min: 0 + type: int32 + volatile: false + group: Failure Detector diff --git a/src/modules/dataman/CMakeLists.txt b/src/modules/dataman/CMakeLists.txt index 6c0a1ab69555..d41622a2f014 100644 --- a/src/modules/dataman/CMakeLists.txt +++ b/src/modules/dataman/CMakeLists.txt @@ -37,4 +37,6 @@ px4_add_module( -Wno-cast-align # TODO: fix and enable SRCS dataman.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/modules/dataman/module.yaml b/src/modules/dataman/module.yaml new file mode 100644 index 000000000000..f0f8fb169da8 --- /dev/null +++ b/src/modules/dataman/module.yaml @@ -0,0 +1,15 @@ +module_name: dataman +parameters: +- definitions: + SYS_DM_BACKEND: + default: 0 + description: + short: Dataman storage backend + reboot_required: true + type: enum + values: + -1: Disabled + 0: default (SD card) + 1: RAM (not persistent) + volatile: false + group: System diff --git a/src/modules/dataman/parameters.c b/src/modules/dataman/parameters.c deleted file mode 100644 index 06fa34564e72..000000000000 --- a/src/modules/dataman/parameters.c +++ /dev/null @@ -1,44 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Dataman storage backend - * - * @group System - * @value -1 Disabled - * @value 0 default (SD card) - * @value 1 RAM (not persistent) - * @boolean - * @reboot_required true - */ -PARAM_DEFINE_INT32(SYS_DM_BACKEND, 0); diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 178e6f21d7ca..805ae9b7c0cc 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -80,6 +80,8 @@ px4_add_module( EKF2Selector.cpp EKF2Selector.hpp + MODULE_CONFIG + module.yaml DEPENDS geo hysteresis diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c deleted file mode 100644 index 28b245e30400..000000000000 --- a/src/modules/ekf2/ekf2_params.c +++ /dev/null @@ -1,1395 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015-2016 Estimation and Control Library (ECL). All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name ECL nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file ekf2_params.c - * Parameter definition for ekf2. - * - * @author Roman Bast - * - */ - -/** - * EKF prediction period - * - * EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. - * Actual filter update will be an integer multiple of IMU update. - * - * @group EKF2 - * @min 1000 - * @max 20000 - * @unit us - */ -PARAM_DEFINE_INT32(EKF2_PREDICT_US, 10000); - -/** - * Magnetometer measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_DELAY, 0); - -/** - * Barometer measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BARO_DELAY, 0); - -/** - * GPS measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_DELAY, 110); - -/** - * Optical flow measurement delay relative to IMU measurements - * - * Assumes measurement is timestamped at trailing edge of integration period - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_DELAY, 20); - -/** - * Range finder measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_DELAY, 5); - -/** - * Airspeed measurement delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_ASP_DELAY, 100); - -/** - * Vision Position Estimator delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_EV_DELAY, 0); - -/** - * Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements - * - * @group EKF2 - * @min 0 - * @max 300 - * @unit ms - * @reboot_required true - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_AVEL_DELAY, 5); - -/** - * Integer bitmask controlling GPS checks. - * - * Set bits to 1 to enable checks. Checks enabled by the following bit positions - * 0 : Minimum required sat count set by EKF2_REQ_NSATS - * 1 : Maximum allowed PDOP set by EKF2_REQ_PDOP - * 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH - * 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV - * 4 : Maximum allowed speed error set by EKF2_REQ_SACC - * 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. - * 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. - * 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. - * 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT - * - * @group EKF2 - * @min 0 - * @max 511 - * @bit 0 Min sat count (EKF2_REQ_NSATS) - * @bit 1 Max PDOP (EKF2_REQ_PDOP) - * @bit 2 Max horizontal position error (EKF2_REQ_EPH) - * @bit 3 Max vertical position error (EKF2_REQ_EPV) - * @bit 4 Max speed error (EKF2_REQ_SACC) - * @bit 5 Max horizontal position rate (EKF2_REQ_HDRIFT) - * @bit 6 Max vertical position rate (EKF2_REQ_VDRIFT) - * @bit 7 Max horizontal speed (EKF2_REQ_HDRIFT) - * @bit 8 Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) - */ -PARAM_DEFINE_INT32(EKF2_GPS_CHECK, 245); - -/** - * Required EPH to use GPS. - * - * @group EKF2 - * @min 2 - * @max 100 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_EPH, 3.0f); - -/** - * Required EPV to use GPS. - * - * @group EKF2 - * @min 2 - * @max 100 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_EPV, 5.0f); - -/** - * Required speed accuracy to use GPS. - * - * @group EKF2 - * @min 0.5 - * @max 5.0 - * @unit m/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_SACC, 0.5f); - -/** - * Required satellite count to use GPS. - * - * @group EKF2 - * @min 4 - * @max 12 - */ -PARAM_DEFINE_INT32(EKF2_REQ_NSATS, 6); - -/** - * Maximum PDOP to use GPS. - * - * @group EKF2 - * @min 1.5 - * @max 5.0 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_PDOP, 2.5f); - -/** - * Maximum horizontal drift speed to use GPS. - * - * @group EKF2 - * @min 0.1 - * @max 1.0 - * @unit m/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_HDRIFT, 0.1f); - -/** - * Maximum vertical drift speed to use GPS. - * - * @group EKF2 - * @min 0.1 - * @max 1.5 - * @decimal 2 - * @unit m/s - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_VDRIFT, 0.2f); - -/** - * Rate gyro noise for covariance prediction. - * - * @group EKF2 - * @min 0.0001 - * @max 0.1 - * @unit rad/s - * @decimal 4 - */ -PARAM_DEFINE_FLOAT(EKF2_GYR_NOISE, 1.5e-2f); - -/** - * Accelerometer noise for covariance prediction. - * - * @group EKF2 - * @min 0.01 - * @max 1.0 - * @unit m/s^2 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_ACC_NOISE, 3.5e-1f); - -/** - * Process noise for IMU rate gyro bias prediction. - * - * @group EKF2 - * @min 0.0 - * @max 0.01 - * @unit rad/s^2 - * @decimal 6 - */ -PARAM_DEFINE_FLOAT(EKF2_GYR_B_NOISE, 1.0e-3f); - -/** - * Process noise for IMU accelerometer bias prediction. - * - * @group EKF2 - * @min 0.0 - * @max 0.01 - * @unit m/s^3 - * @decimal 6 - */ -PARAM_DEFINE_FLOAT(EKF2_ACC_B_NOISE, 3.0e-3f); - -/** - * Process noise for body magnetic field prediction. - * - * @group EKF2 - * @min 0.0 - * @max 0.1 - * @unit gauss/s - * @decimal 6 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_B_NOISE, 1.0e-4f); - -/** - * Process noise for earth magnetic field prediction. - * - * @group EKF2 - * @min 0.0 - * @max 0.1 - * @unit gauss/s - * @decimal 6 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_E_NOISE, 1.0e-3f); - -/** - * Process noise spectral density for wind velocity prediction. - * - * When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. - * - * @group EKF2 - * @min 0.0 - * @max 1.0 - * @unit m/s^2/sqrt(Hz) - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_WIND_NSD, 1.0e-2f); - -/** - * Measurement noise for gps horizontal velocity. - * - * @group EKF2 - * @min 0.01 - * @max 5.0 - * @unit m/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_V_NOISE, 0.3f); - -/** - * Measurement noise for gps position. - * - * @group EKF2 - * @min 0.01 - * @max 10.0 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_P_NOISE, 0.5f); - -/** - * Measurement noise for non-aiding position hold. - * - * @group EKF2 - * @min 0.5 - * @max 50.0 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_NOAID_NOISE, 10.0f); - -/** - * Measurement noise for barometric altitude. - * - * @group EKF2 - * @min 0.01 - * @max 15.0 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_BARO_NOISE, 3.5f); - -/** - * Measurement noise for magnetic heading fusion. - * - * @group EKF2 - * @min 0.01 - * @max 1.0 - * @unit rad - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_HEAD_NOISE, 0.3f); - -/** - * Measurement noise for magnetometer 3-axis fusion. - * - * @group EKF2 - * @min 0.001 - * @max 1.0 - * @unit gauss - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_NOISE, 5.0e-2f); - -/** - * Measurement noise for airspeed fusion. - * - * @group EKF2 - * @min 0.5 - * @max 5.0 - * @unit m/s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_EAS_NOISE, 1.4f); - -/** - * Gate size for synthetic sideslip fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BETA_GATE, 5.0f); - -/** - * Noise for synthetic sideslip fusion. - * - * @group EKF2 - * @min 0.1 - * @max 1.0 - * @unit m/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_BETA_NOISE, 0.3f); - -/** - * Gate size for magnetic heading fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_HDG_GATE, 2.6f); - -/** - * Gate size for magnetometer XYZ component fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_GATE, 3.0f); - -/** - * Integer bitmask controlling handling of magnetic declination. - * - * Set bits in the following positions to enable functions. - * 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. - * 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. - * 2 : Set to true to always use the declination as an observation when 3-axis magnetometer fusion is being used. - * - * @group EKF2 - * @min 0 - * @max 7 - * @bit 0 use geo_lookup declination - * @bit 1 save EKF2_MAG_DECL on disarm - * @bit 2 use declination as an observation - * @reboot_required true - */ -PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7); - -/** - * Type of magnetometer fusion - * - * Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fuson of magnetomer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. - * If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. - * If set to 'Magnetic heading' magnetic heading fusion is used at all times - * If set to '3-axis' 3-axis field fusion is used at all times. - * If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight. - * If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. - * If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). Other external sources of yaw may be used if selected via the EKF2_AID_MASK parameter. - * @group EKF2 - * @value 0 Automatic - * @value 1 Magnetic heading - * @value 2 3-axis - * @value 3 VTOL custom - * @value 4 MC custom - * @value 5 None - * @reboot_required true - */ -PARAM_DEFINE_INT32(EKF2_MAG_TYPE, 0); - -/** - * Horizontal acceleration threshold used by automatic selection of magnetometer fusion method. - * - * This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion. - * - * @group EKF2 - * @min 0.0 - * @max 5.0 - * @unit m/s^2 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_ACCLIM, 0.5f); - -/** - * Yaw rate threshold used by automatic selection of magnetometer fusion method. - * - * This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion. - * - * @group EKF2 - * @min 0.0 - * @max 1.0 - * @unit rad/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_YAWLIM, 0.25f); - -/** - * Gate size for barometric and GPS height fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BARO_GATE, 5.0f); - -/** - * Baro deadzone range for height fusion - * - * Sets the value of deadzone applied to negative baro innovations. - * Deadzone is enabled when EKF2_GND_EFF_DZ > 0. - * - * @group EKF2 - * @min 0.0 - * @max 10.0 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GND_EFF_DZ, 4.0f); - -/** - * Height above ground level for ground effect zone - * - * Sets the maximum distance to the ground level where negative baro innovations are expected. - * - * @group EKF2 - * @min 0.0 - * @max 5.0 - * @unit m - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GND_MAX_HGT, 0.5f); - -/** - * Gate size for GPS horizontal position fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_P_GATE, 5.0f); - -/** - * Gate size for GPS velocity fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 5.0f); - -/** - * Gate size for TAS fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_TAS_GATE, 3.0f); - -/** - * Integer bitmask controlling data fusion and aiding methods. - * - * Set bits in the following positions to enable: - * 0 : Set to true to use GPS data if available - * 1 : Set to true to use optical flow data if available - * 2 : Set to true to inhibit IMU delta velocity bias estimation - * 3 : Set to true to enable vision position fusion - * 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true. - * 5 : Set to true to enable multi-rotor drag specific force fusion - * 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used - * 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true. - * - * @group EKF2 - * @min 0 - * @max 511 - * @bit 0 use GPS - * @bit 1 use optical flow - * @bit 2 inhibit IMU bias estimation - * @bit 3 vision position fusion - * @bit 4 vision yaw fusion - * @bit 5 multi-rotor drag fusion - * @bit 6 rotate external vision - * @bit 7 GPS yaw fusion - * @bit 8 vision velocity fusion - * @reboot_required true - */ -PARAM_DEFINE_INT32(EKF2_AID_MASK, 1); - -/** - * Determines the primary source of height data used by the EKF. - * - * The range sensor option should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. - * - * @group EKF2 - * @value 0 Barometric pressure - * @value 1 GPS - * @value 2 Range sensor - * @value 3 Vision - * @reboot_required true - */ -PARAM_DEFINE_INT32(EKF2_HGT_MODE, 0); - -/** - * Integer bitmask controlling fusion sources of the terrain estimator - * - * Set bits in the following positions to enable: - * 0 : Set to true to use range finder data if available - * 1 : Set to true to use optical flow data if available - * - * @group EKF2 - * @min 0 - * @max 3 - * @bit 0 use range finder - * @bit 1 use optical flow - */ -PARAM_DEFINE_INT32(EKF2_TERR_MASK, 3); - -/** - * Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid. - * - * @group EKF2 - * @group EKF2 - * @min 500000 - * @max 10000000 - * @unit us - */ -PARAM_DEFINE_INT32(EKF2_NOAID_TOUT, 5000000); - -/** - * Measurement noise for range finder fusion - * - * @group EKF2 - * @min 0.01 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_NOISE, 0.1f); - -/** - * Range finder range dependant noise scaler. - * - * Specifies the increase in range finder noise with range. - * - * @group EKF2 - * @min 0.0 - * @max 0.2 - * @unit m/m - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_SFE, 0.05f); - -/** - * Gate size for range finder fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_GATE, 5.0f); - -/** - * Expected range finder reading when on ground. - * - * If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. - * - * @group EKF2 - * @min 0.01 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_MIN_RNG, 0.1f); - -/** - * Whether to set the external vision observation noise from the parameter or from vision message - * - * If set to true the observation noise is set from the parameters directly, if set to false the measurement noise is taken from the vision message and the parameter are used as a lower bound. - * - * @boolean - * @group EKF2 - */ -PARAM_DEFINE_INT32(EKF2_EV_NOISE_MD, 0); - -/** - * Measurement noise for vision position observations used to lower bound or replace the uncertainty included in the message - * - * @group EKF2 - * @min 0.01 - * @unit m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_EVP_NOISE, 0.1f); - -/** - * Measurement noise for vision velocity observations used to lower bound or replace the uncertainty included in the message - * - * @group EKF2 - * @min 0.01 - * @unit m/s - * @decimal 2 -*/ -PARAM_DEFINE_FLOAT(EKF2_EVV_NOISE, 0.1f); - -/** - * Measurement noise for vision angle observations used to lower bound or replace the uncertainty included in the message - * - * @group EKF2 - * @min 0.05 - * @unit rad - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_EVA_NOISE, 0.05f); - -/** - * Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum - * - * @group EKF2 - * @min 0.05 - * @unit rad/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_N_MIN, 0.15f); - -/** - * Measurement noise for the optical flow sensor. - * - * (when it's reported quality metric is at the minimum set by EKF2_OF_QMIN). - * The following condition must be met: EKF2_OF_N_MAXN >= EKF2_OF_N_MIN - * - * @group EKF2 - * @min 0.05 - * @unit rad/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_N_MAX, 0.5f); - -/** - * Optical Flow data will only be used if the sensor reports a quality metric >= EKF2_OF_QMIN. - * - * @group EKF2 - * @min 0 - * @max 255 - */ -PARAM_DEFINE_INT32(EKF2_OF_QMIN, 1); - -/** - * Gate size for optical flow fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_GATE, 3.0f); - -/** - * Terrain altitude process noise - accounts for instability in vehicle height estimate - * - * @group EKF2 - * @min 0.5 - * @unit m/s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_TERR_NOISE, 5.0f); - -/** - * Magnitude of terrain gradient - * - * @group EKF2 - * @min 0.0 - * @unit m/m - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_TERR_GRAD, 0.5f); - -/** - * X position of IMU in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_IMU_POS_X, 0.0f); - -/** - * Y position of IMU in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_IMU_POS_Y, 0.0f); - -/** - * Z position of IMU in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_IMU_POS_Z, 0.0f); - -/** - * X position of GPS antenna in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_POS_X, 0.0f); - -/** - * Y position of GPS antenna in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_POS_Y, 0.0f); - -/** - * Z position of GPS antenna in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_GPS_POS_Z, 0.0f); - -/** - * X position of range finder origin in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_POS_X, 0.0f); - -/** - * Y position of range finder origin in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_POS_Y, 0.0f); - -/** - * Z position of range finder origin in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_POS_Z, 0.0f); - -/** - * X position of optical flow focal point in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_POS_X, 0.0f); - -/** - * Y position of optical flow focal point in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_POS_Y, 0.0f); - -/** - * Z position of optical flow focal point in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_OF_POS_Z, 0.0f); - -/** -* X position of VI sensor focal point in body frame (forward axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_EV_POS_X, 0.0f); - -/** - * Y position of VI sensor focal point in body frame (right axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_EV_POS_Y, 0.0f); - -/** - * Z position of VI sensor focal point in body frame (down axis with origin relative to vehicle centre of gravity) - * - * @group EKF2 - * @unit m - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_EV_POS_Z, 0.0f); - -/** -* Airspeed fusion threshold. -* -* A value of zero will deactivate airspeed fusion. Any other positive -* value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed. -* Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS. -* Use EKF2_FUSE_BETA to activate sideslip fusion. -* -* @group EKF2 -* @min 0.0 -* @unit m/s -* @decimal 1 -*/ -PARAM_DEFINE_FLOAT(EKF2_ARSP_THR, 0.0f); - -/** -* Boolean determining if synthetic sideslip measurements should fused. -* -* A value of 1 indicates that fusion is active -* Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. -* Use EKF2_ARSP_THR to activate airspeed fusion. -* -* @group EKF2 -* @boolean -*/ -PARAM_DEFINE_INT32(EKF2_FUSE_BETA, 0); - -/** - - * Time constant of the velocity output prediction and smoothing filter - * - * @group EKF2 - * @max 1.0 - * @unit s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_TAU_VEL, 0.25f); - -/** - * Time constant of the position output prediction and smoothing filter. Controls how tightly the output track the EKF states. - * - * @group EKF2 - * @min 0.1 - * @max 1.0 - * @unit s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_TAU_POS, 0.25f); - -/** - * 1-sigma IMU gyro switch-on bias - * - * @group EKF2 - * @min 0.0 - * @max 0.2 - * @unit rad/s - * @reboot_required true - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_GBIAS_INIT, 0.1f); - -/** - * 1-sigma IMU accelerometer switch-on bias - * - * @group EKF2 - * @min 0.0 - * @max 0.5 - * @unit m/s^2 - * @reboot_required true - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_ABIAS_INIT, 0.2f); - -/** - * 1-sigma tilt angle uncertainty after gravity vector alignment - * - * @group EKF2 - * @min 0.0 - * @max 0.5 - * @unit rad - * @reboot_required true - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_ANGERR_INIT, 0.1f); - -/** - * Range sensor pitch offset. - * - * @group EKF2 - * @min -0.75 - * @max 0.75 - * @unit rad - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_PITCH, 0.0f); - -/** - * Range sensor aid. - * - * If this parameter is enabled then the estimator will make use of the range finder measurements - * to estimate it's height even if range sensor is not the primary height source. It will only do so if conditions - * for range measurement fusion are met. This enables the range finder to be used during low speed and low altitude - * operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state - * estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does - * not occur until above EKF2_RNG_A_HMAX. If vehicle motion causes repeated switching between the primary height - * sensor and range finder, an offset in the local position origin can accumulate. Also range finder measurements - * are less reliable and can experience unexpected errors. For these reasons, if accurate control of height - * relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors - * are severe enough to cause problems with landing and takeoff. - * - * @group EKF2 - * @value 0 Range aid disabled - * @value 1 Range aid enabled - */ -PARAM_DEFINE_INT32(EKF2_RNG_AID, 1); - -/** - * Maximum horizontal velocity allowed for range aid mode. - * - * If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements - * to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). - * - * @group EKF2 - * @min 0.1 - * @max 2 - * @unit m/s - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_A_VMAX, 1.0f); - -/** - * Maximum absolute altitude (height above ground level) allowed for range aid mode. - * - * If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements - * to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). - * - * @group EKF2 - * @min 1.0 - * @max 10.0 - * @unit m - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_A_HMAX, 5.0f); - -/** - * Gate size used for innovation consistency checks for range aid fusion - * - * A lower value means HAGL needs to be more stable in order to use range finder for height estimation - * in range aid mode - * - * @group EKF2 - * @unit SD - * @min 0.1 - * @max 5.0 - */ -PARAM_DEFINE_FLOAT(EKF2_RNG_A_IGATE, 1.0f); - -/** - * Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s) - * - * - * @group EKF2 - * @unit s - * @min 0.1 - * @max 5 -*/ -PARAM_DEFINE_FLOAT(EKF2_RNG_QLTY_T, 1.0f); - -/** - * Gate size used for range finder kinematic consistency check - * - * To be used, the time derivative of the distance sensor measurements projected on the vertical axis - * needs to be statistically consistent with the estimated vertical velocity of the drone. - * - * Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). - * - * Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate. - * - * @group EKF2 - * @unit SD - * @min 0.1 - * @max 5.0 -*/ -PARAM_DEFINE_FLOAT(EKF2_RNG_K_GATE, 1.0f); - -/** - * Gate size for vision velocity estimate fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 -*/ -PARAM_DEFINE_FLOAT(EKF2_EVV_GATE, 3.0f); - -/** - * Gate size for vision position fusion - * - * Sets the number of standard deviations used by the innovation consistency test. - * @group EKF2 - * @min 1.0 - * @unit SD - * @decimal 1 -*/ -PARAM_DEFINE_FLOAT(EKF2_EVP_GATE, 5.0f); - -/** - * Specific drag force observation noise variance used by the multi-rotor specific drag force model. - * - * Increasing this makes the multi-rotor wind estimates adjust more slowly. - * - * @group EKF2 - * @min 0.5 - * @max 10.0 - * @unit (m/s^2)^2 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_DRAG_NOISE, 2.5f); - -/** - * X-axis ballistic coefficient used for multi-rotor wind estimation. - * - * This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_X paraemter should be set initially to the ratio of mass / projected frontal area and adjusted together with EKF2_MCOEF to minimise variance of the X-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. Set this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. - * - * @group EKF2 - * @min 0.0 - * @max 200.0 - * @unit kg/m^2 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BCOEF_X, 100.0f); - -/** - * Y-axis ballistic coefficient used for multi-rotor wind estimation. - * - * This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_Y paraemter should be set initially to the ratio of mass / projected side area and adjusted together with EKF2_MCOEF to minimise variance of the Y-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. et this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. - * - * @group EKF2 - * @min 0.0 - * @max 200.0 - * @unit kg/m^2 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_BCOEF_Y, 100.0f); - -/** - * propeller momentum drag coefficient used for multi-rotor wind estimation. - * - * This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. For example, if flying at 10 m/s at sea level conditions produces a rotor induced drag deceleration of 1.5 m/s/s when the multi-copter levelled to zero roll/pitch, then EKF2_MCOEF would be set to 0.15 = (1.5/10.0). Set EKF2_MCOEF to a positive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. The EKF2_MCOEF parameter should be adjusted together with EKF2_BCOEF_X and EKF2_BCOEF_Y to minimise variance of the X and y axis drag specific force innovation sequences. - * - * @group EKF2 - * @min 0 - * @max 1.0 - * @unit 1/s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_MCOEF, 0.15f); - - -/** - * Upper limit on airspeed along individual axes used to correct baro for position error effects - * - * @group EKF2 - * @min 5.0 - * @max 50.0 - * @unit m/s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_ASPD_MAX, 20.0f); - -/** - * Static pressure position error coefficient for the positive X axis - * - * This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. - * If the baro height estimate rises during forward flight, then this will be a negative number. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_XP, 0.0f); - -/** - * Static pressure position error coefficient for the negative X axis. - * - * This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. - * If the baro height estimate rises during backwards flight, then this will be a negative number. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_XN, 0.0f); - -/** - * Pressure position error coefficient for the positive Y axis. - * - * This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. - * If the baro height estimate rises during sideways flight to the right, then this will be a negative number. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_YP, 0.0f); - -/** - * Pressure position error coefficient for the negative Y axis. - * - * This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. - * If the baro height estimate rises during sideways flight to the left, then this will be a negative number. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_YN, 0.0f); - -/** - * Static pressure position error coefficient for the Z axis. - * - * This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis. - * - * @group EKF2 - * @min -0.5 - * @max 0.5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_PCOEF_Z, 0.0f); - -/** - * Accelerometer bias learning limit. - * - * The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value. - * - * @group EKF2 - * @min 0.0 - * @max 0.8 - * @unit m/s^2 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_ABL_LIM, 0.4f); - -/** - * Maximum IMU accel magnitude that allows IMU bias learning. - * - * If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited. - * This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates. - * - * @group EKF2 - * @min 20.0 - * @max 200.0 - * @unit m/s^2 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_ABL_ACCLIM, 25.0f); - -/** - * Maximum IMU gyro angular rate magnitude that allows IMU bias learning. - * - * If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited. - * This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates. - * - * @group EKF2 - * @min 2.0 - * @max 20.0 - * @unit rad/s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_ABL_GYRLIM, 3.0f); - -/** - * Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning. - * - * The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. - * This parameter controls the time constant of the decay. - * - * @group EKF2 - * @min 0.1 - * @max 1.0 - * @unit s - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(EKF2_ABL_TAU, 0.5f); - -/** - * Required GPS health time on startup - * - * Minimum continuous period without GPS failure required to mark a healthy GPS status. - * It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle. - * - * @group EKF2 - * @min 0.1 - * @decimal 1 - * @unit s - * @reboot_required true - */ -PARAM_DEFINE_FLOAT(EKF2_REQ_GPS_H, 10.0f); - -/** - * Magnetic field strength test selection - * - * When set, the EKF checks the strength of the magnetic field - * to decide whether the magnetometer data is valid. - * If GPS data is received, the magnetic field is compared to a World - * Magnetic Model (WMM), otherwise an average value is used. - * This check is useful to reject occasional hard iron disturbance. - * - * @group EKF2 - * @boolean - */ -PARAM_DEFINE_INT32(EKF2_MAG_CHECK, 1); - -/** - * Enable synthetic magnetometer Z component measurement. - * - * Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. - * For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated - * using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter - * will only have an effect if the global position of the drone is known. - * For 3D mag fusion the magnetometer Z measurement will simply be ingored instead of fusing the synthetic value. - * - * @group EKF2 - * @boolean -*/ -PARAM_DEFINE_INT32(EKF2_SYNT_MAG_Z, 0); - -/** - * Default value of true airspeed used in EKF-GSF AHRS calculation. - * - * If no airspeed measurements are avalable, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. - * - * @group EKF2 - * @min 0.0 - * @unit m/s - * @max 100.0 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_GSF_TAS, 15.0f); diff --git a/src/modules/ekf2/ekf2_params_multi.c b/src/modules/ekf2/ekf2_params_multi.c deleted file mode 100644 index cd06198dc161..000000000000 --- a/src/modules/ekf2/ekf2_params_multi.c +++ /dev/null @@ -1,58 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Multi-EKF IMUs - * - * Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. - * Requires SENS_IMU_MODE 0. - * - * @group EKF2 - * @reboot_required true - * @min 0 - * @max 4 - */ -PARAM_DEFINE_INT32(EKF2_MULTI_IMU, 0); - -/** - * Multi-EKF Magnetometers. - * - * Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. - * Requires SENS_MAG_MODE 0. - * - * @group EKF2 - * @reboot_required true - * @min 0 - * @max 4 - */ -PARAM_DEFINE_INT32(EKF2_MULTI_MAG, 0); diff --git a/src/modules/ekf2/ekf2_params_selector.c b/src/modules/ekf2/ekf2_params_selector.c deleted file mode 100644 index 43a630fe8fb3..000000000000 --- a/src/modules/ekf2/ekf2_params_selector.c +++ /dev/null @@ -1,81 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Selector error reduce threshold - * - * EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced. - * - * @group EKF2 - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_ERR_RED, 0.2f); - -/** - * Selector angular rate threshold - * - * EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error. - * - * @group EKF2 - * @unit deg/s - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_IMU_RAT, 7.0f); - -/** - * Selector angular threshold. - * - * EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty. - * - * @group EKF2 - * @unit deg - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_IMU_ANG, 15.0f); - -/** - * Selector acceleration threshold - * - * EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error. - * - * @group EKF2 - * @unit m/s^2 - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_IMU_ACC, 1.0f); - -/** - * Selector angular threshold. - * - * EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty. - * - * @group EKF2 - * @unit m/s - */ -PARAM_DEFINE_FLOAT(EKF2_SEL_IMU_VEL, 2.0f); diff --git a/src/modules/ekf2/ekf2_params_volatile.c b/src/modules/ekf2/ekf2_params_volatile.c deleted file mode 100644 index 5b947a5cf818..000000000000 --- a/src/modules/ekf2/ekf2_params_volatile.c +++ /dev/null @@ -1,43 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Magnetic declination - * - * @group EKF2 - * @volatile - * @category system - * @unit deg - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_MAG_DECL, 0); diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml new file mode 100644 index 000000000000..8cdb9fd1b5d0 --- /dev/null +++ b/src/modules/ekf2/module.yaml @@ -0,0 +1,1200 @@ +module_name: ekf2 +parameters: + - definitions: + EKF2_ABIAS_INIT: + decimal: 2 + default: 0.2 + description: + short: 1-sigma IMU accelerometer switch-on bias + max: 0.5 + min: 0.0 + reboot_required: true + type: float + unit: m/s^2 + volatile: false + EKF2_ABL_ACCLIM: + decimal: 1 + default: 25.0 + description: + long: If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates. + short: Maximum IMU accel magnitude that allows IMU bias learning + max: 200.0 + min: 20.0 + type: float + unit: m/s^2 + volatile: false + EKF2_ABL_GYRLIM: + decimal: 1 + default: 3.0 + description: + long: If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates. + short: Maximum IMU gyro angular rate magnitude that allows IMU bias learning + max: 20.0 + min: 2.0 + type: float + unit: rad/s + volatile: false + EKF2_ABL_LIM: + decimal: 2 + default: 0.4 + description: + long: The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value. + short: Accelerometer bias learning limit + max: 0.8 + min: 0.0 + type: float + unit: m/s^2 + volatile: false + EKF2_ABL_TAU: + decimal: 2 + default: 0.5 + description: + long: The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay. + short: Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning + max: 1.0 + min: 0.1 + type: float + unit: s + volatile: false + EKF2_ACC_B_NOISE: + decimal: 6 + default: 0.003 + description: + short: Process noise for IMU accelerometer bias prediction + max: 0.01 + min: 0.0 + type: float + unit: m/s^3 + volatile: false + EKF2_ACC_NOISE: + decimal: 2 + default: 0.35 + description: + short: Accelerometer noise for covariance prediction + max: 1.0 + min: 0.01 + type: float + unit: m/s^2 + volatile: false + EKF2_AID_MASK: + bit: + 0: use GPS + 1: use optical flow + 2: inhibit IMU bias estimation + 3: vision position fusion + 4: vision yaw fusion + 5: multi-rotor drag fusion + 6: rotate external vision + 7: GPS yaw fusion + 8: vision velocity fusion + default: 1 + description: + long: 'Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU delta velocity bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true. 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true.' + short: Integer bitmask controlling data fusion and aiding methods + max: 511 + min: 0 + reboot_required: true + type: bitmask + volatile: false + EKF2_ANGERR_INIT: + decimal: 3 + default: 0.1 + description: + short: 1-sigma tilt angle uncertainty after gravity vector alignment + max: 0.5 + min: 0.0 + reboot_required: true + type: float + unit: rad + volatile: false + EKF2_ARSP_THR: + decimal: 1 + default: 0.0 + description: + long: A value of zero will deactivate airspeed fusion. Any other positive value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed. Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_FUSE_BETA to activate sideslip fusion. + short: Airspeed fusion threshold + min: 0.0 + type: float + unit: m/s + volatile: false + EKF2_ASPD_MAX: + decimal: 1 + default: 20.0 + description: + short: Upper limit on airspeed along individual axes used to correct baro for position error effects + max: 50.0 + min: 5.0 + type: float + unit: m/s + volatile: false + EKF2_ASP_DELAY: + decimal: 1 + default: 100 + description: + short: Airspeed measurement delay relative to IMU measurements + max: 300 + min: 0 + reboot_required: true + type: float + unit: ms + volatile: false + EKF2_AVEL_DELAY: + decimal: 1 + default: 5 + description: + short: Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements + max: 300 + min: 0 + reboot_required: true + type: float + unit: ms + volatile: false + EKF2_BARO_DELAY: + decimal: 1 + default: 0 + description: + short: Barometer measurement delay relative to IMU measurements + max: 300 + min: 0 + reboot_required: true + type: float + unit: ms + volatile: false + EKF2_BARO_GATE: + decimal: 1 + default: 5.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for barometric and GPS height fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_BARO_NOISE: + decimal: 2 + default: 3.5 + description: + short: Measurement noise for barometric altitude + max: 15.0 + min: 0.01 + type: float + unit: m + volatile: false + EKF2_BCOEF_X: + decimal: 1 + default: 100.0 + description: + long: This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_X paraemter should be set initially to the ratio of mass / projected frontal area and adjusted together with EKF2_MCOEF to minimise variance of the X-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. Set this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. + short: X-axis ballistic coefficient used for multi-rotor wind estimation + max: 200.0 + min: 0.0 + type: float + unit: kg/m^2 + volatile: false + EKF2_BCOEF_Y: + decimal: 1 + default: 100.0 + description: + long: This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_Y paraemter should be set initially to the ratio of mass / projected side area and adjusted together with EKF2_MCOEF to minimise variance of the Y-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. et this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. + short: Y-axis ballistic coefficient used for multi-rotor wind estimation + max: 200.0 + min: 0.0 + type: float + unit: kg/m^2 + volatile: false + EKF2_BETA_GATE: + decimal: 1 + default: 5.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for synthetic sideslip fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_BETA_NOISE: + decimal: 2 + default: 0.3 + description: + short: Noise for synthetic sideslip fusion + max: 1.0 + min: 0.1 + type: float + unit: m/s + volatile: false + EKF2_DECL_TYPE: + bit: + 0: use geo_lookup declination + 1: save EKF2_MAG_DECL on disarm + 2: use declination as an observation + default: 7 + description: + long: 'Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. 2 : Set to true to always use the declination as an observation when 3-axis magnetometer fusion is being used.' + short: Integer bitmask controlling handling of magnetic declination + max: 7 + min: 0 + reboot_required: true + type: bitmask + volatile: false + EKF2_DRAG_NOISE: + decimal: 2 + default: 2.5 + description: + long: Increasing this makes the multi-rotor wind estimates adjust more slowly. + short: Specific drag force observation noise variance used by the multi-rotor specific drag force model + max: 10.0 + min: 0.5 + type: float + unit: (m/s^2)^2 + volatile: false + EKF2_EAS_NOISE: + decimal: 1 + default: 1.4 + description: + short: Measurement noise for airspeed fusion + max: 5.0 + min: 0.5 + type: float + unit: m/s + volatile: false + EKF2_EVA_NOISE: + decimal: 2 + default: 0.05 + description: + short: Measurement noise for vision angle observations used to lower bound or replace the uncertainty included in the message + min: 0.05 + type: float + unit: rad + volatile: false + EKF2_EVP_GATE: + decimal: 1 + default: 5.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for vision position fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_EVP_NOISE: + decimal: 2 + default: 0.1 + description: + short: Measurement noise for vision position observations. + long: Used to lower bound or replace the uncertainty included in the message + min: 0.01 + type: float + unit: m + volatile: false + EKF2_EVV_GATE: + decimal: 1 + default: 3.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for vision velocity estimate fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_EVV_NOISE: + decimal: 2 + default: 0.1 + description: + short: Measurement noise for vision velocity observations + long: Used to lower bound or replace the uncertainty included in the message + min: 0.01 + type: float + unit: m/s + volatile: false + EKF2_EV_DELAY: + decimal: 1 + default: 0 + description: + short: Vision Position Estimator delay relative to IMU measurements + max: 300 + min: 0 + reboot_required: true + type: float + unit: ms + volatile: false + EKF2_EV_NOISE_MD: + default: 0 + description: + long: If set to true the observation noise is set from the parameters directly, if set to false the measurement noise is taken from the vision message and the parameter are used as a lower bound. + short: Whether to set the external vision observation noise from the parameter or from vision message + type: boolean + volatile: false + EKF2_EV_POS_X: + decimal: 3 + default: 0.0 + description: + short: X position of VI sensor focal point in body frame (forward axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_EV_POS_Y: + decimal: 3 + default: 0.0 + description: + short: Y position of VI sensor focal point in body frame (right axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_EV_POS_Z: + decimal: 3 + default: 0.0 + description: + short: Z position of VI sensor focal point in body frame (down axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_FUSE_BETA: + default: 0 + description: + long: A value of 1 indicates that fusion is active Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion. + short: Boolean determining if synthetic sideslip measurements should fused + type: boolean + volatile: false + EKF2_GBIAS_INIT: + decimal: 2 + default: 0.1 + description: + short: 1-sigma IMU gyro switch-on bias + max: 0.2 + min: 0.0 + reboot_required: true + type: float + unit: rad/s + volatile: false + EKF2_GND_EFF_DZ: + decimal: 1 + default: 4.0 + description: + long: Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0. + short: Baro deadzone range for height fusion + max: 10.0 + min: 0.0 + type: float + unit: m + volatile: false + EKF2_GND_MAX_HGT: + decimal: 1 + default: 0.5 + description: + long: Sets the maximum distance to the ground level where negative baro innovations are expected. + short: Height above ground level for ground effect zone + max: 5.0 + min: 0.0 + type: float + unit: m + volatile: false + EKF2_GPS_CHECK: + bit: + 0: Min sat count (EKF2_REQ_NSATS) + 1: Max PDOP (EKF2_REQ_PDOP) + 2: Max horizontal position error (EKF2_REQ_EPH) + 3: Max vertical position error (EKF2_REQ_EPV) + 4: Max speed error (EKF2_REQ_SACC) + 5: Max horizontal position rate (EKF2_REQ_HDRIFT) + 6: Max vertical position rate (EKF2_REQ_VDRIFT) + 7: Max horizontal speed (EKF2_REQ_HDRIFT) + 8: Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) + default: 245 + description: + long: 'Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Maximum allowed PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT' + short: Integer bitmask controlling GPS checks + max: 511 + min: 0 + type: bitmask + volatile: false + EKF2_GPS_DELAY: + decimal: 1 + default: 110 + description: + short: GPS measurement delay relative to IMU measurements + max: 300 + min: 0 + reboot_required: true + type: float + unit: ms + volatile: false + EKF2_GPS_POS_X: + decimal: 3 + default: 0.0 + description: + short: X position of GPS antenna in body frame (forward axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_GPS_POS_Y: + decimal: 3 + default: 0.0 + description: + short: Y position of GPS antenna in body frame (right axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_GPS_POS_Z: + decimal: 3 + default: 0.0 + description: + short: Z position of GPS antenna in body frame (down axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_GPS_P_GATE: + decimal: 1 + default: 5.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for GPS horizontal position fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_GPS_P_NOISE: + decimal: 2 + default: 0.5 + description: + short: Measurement noise for gps position + max: 10.0 + min: 0.01 + type: float + unit: m + volatile: false + EKF2_GPS_V_GATE: + decimal: 1 + default: 5.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for GPS velocity fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_GPS_V_NOISE: + decimal: 2 + default: 0.3 + description: + short: Measurement noise for gps horizontal velocity + max: 5.0 + min: 0.01 + type: float + unit: m/s + volatile: false + EKF2_GSF_TAS: + decimal: 1 + default: 15.0 + description: + long: If no airspeed measurements are avalable, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. + short: Default value of true airspeed used in EKF-GSF AHRS calculation + max: 100.0 + min: 0.0 + type: float + unit: m/s + volatile: false + EKF2_GYR_B_NOISE: + decimal: 6 + default: 0.001 + description: + short: Process noise for IMU rate gyro bias prediction + max: 0.01 + min: 0.0 + type: float + unit: rad/s^2 + volatile: false + EKF2_GYR_NOISE: + decimal: 4 + default: 0.015 + description: + short: Rate gyro noise for covariance prediction + max: 0.1 + min: 0.0001 + type: float + unit: rad/s + volatile: false + EKF2_HDG_GATE: + decimal: 1 + default: 2.6 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for magnetic heading fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_HEAD_NOISE: + decimal: 2 + default: 0.3 + description: + short: Measurement noise for magnetic heading fusion + max: 1.0 + min: 0.01 + type: float + unit: rad + volatile: false + EKF2_HGT_MODE: + default: 0 + description: + long: The range sensor option should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. + short: Determines the primary source of height data used by the EKF + reboot_required: true + type: enum + values: + 0: Barometric pressure + 1: GPS + 2: Range sensor + 3: Vision + volatile: false + EKF2_IMU_POS_X: + decimal: 3 + default: 0.0 + description: + short: X position of IMU in body frame (forward axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_IMU_POS_Y: + decimal: 3 + default: 0.0 + description: + short: Y position of IMU in body frame (right axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_IMU_POS_Z: + decimal: 3 + default: 0.0 + description: + short: Z position of IMU in body frame (down axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_MAG_ACCLIM: + decimal: 2 + default: 0.5 + description: + long: This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion. + short: Horizontal acceleration threshold used by automatic selection of magnetometer fusion method + max: 5.0 + min: 0.0 + type: float + unit: m/s^2 + volatile: false + EKF2_MAG_B_NOISE: + decimal: 6 + default: 0.0001 + description: + short: Process noise for body magnetic field prediction + max: 0.1 + min: 0.0 + type: float + unit: gauss/s + volatile: false + EKF2_MAG_CHECK: + default: 1 + description: + long: When set, the EKF checks the strength of the magnetic field to decide whether the magnetometer data is valid. If GPS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. + short: Magnetic field strength test selection + type: boolean + volatile: false + EKF2_MAG_DELAY: + decimal: 1 + default: 0 + description: + short: Magnetometer measurement delay relative to IMU measurements + max: 300 + min: 0 + reboot_required: true + type: float + unit: ms + volatile: false + EKF2_MAG_E_NOISE: + decimal: 6 + default: 0.001 + description: + short: Process noise for earth magnetic field prediction + max: 0.1 + min: 0.0 + type: float + unit: gauss/s + volatile: false + EKF2_MAG_GATE: + decimal: 1 + default: 3.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for magnetometer XYZ component fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_MAG_NOISE: + decimal: 3 + default: 0.05 + description: + short: Measurement noise for magnetometer 3-axis fusion + max: 1.0 + min: 0.001 + type: float + unit: gauss + volatile: false + EKF2_MAG_TYPE: + default: 0 + description: + long: Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fuson of magnetomer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. If set to 'Magnetic heading' magnetic heading fusion is used at all times If set to '3-axis' 3-axis field fusion is used at all times. If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight. If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). Other external sources of yaw may be used if selected via the EKF2_AID_MASK parameter. + short: Type of magnetometer fusion + reboot_required: true + type: enum + values: + 0: Automatic + 1: Magnetic heading + 2: 3-axis + 3: VTOL custom + 4: MC custom + 5: None + volatile: false + EKF2_MAG_YAWLIM: + decimal: 2 + default: 0.25 + description: + long: This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion. + short: Yaw rate threshold used by automatic selection of magnetometer fusion method + max: 1.0 + min: 0.0 + type: float + unit: rad/s + volatile: false + EKF2_MCOEF: + decimal: 2 + default: 0.15 + description: + long: This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. For example, if flying at 10 m/s at sea level conditions produces a rotor induced drag deceleration of 1.5 m/s/s when the multi-copter levelled to zero roll/pitch, then EKF2_MCOEF would be set to 0.15 = (1.5/10.0). Set EKF2_MCOEF to a positive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. The EKF2_MCOEF parameter should be adjusted together with EKF2_BCOEF_X and EKF2_BCOEF_Y to minimise variance of the X and y axis drag specific force innovation sequences. + short: propeller momentum drag coefficient used for multi-rotor wind estimation + max: 1.0 + min: 0 + type: float + unit: 1/s + volatile: false + EKF2_MIN_RNG: + decimal: 2 + default: 0.1 + description: + long: If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. + short: Expected range finder reading when on ground + min: 0.01 + type: float + unit: m + volatile: false + EKF2_NOAID_NOISE: + decimal: 1 + default: 10.0 + description: + short: Measurement noise for non-aiding position hold + max: 50.0 + min: 0.5 + type: float + unit: m + volatile: false + EKF2_NOAID_TOUT: + default: 5000000 + description: + short: Timeout before reporting horizontal nav solution as invalid. + long: Max lapsed time from last measurements fusion that constrain velocity drift before reporting horizontal nav solution as invalid + max: 10000000 + min: 500000 + type: int32 + unit: us + volatile: false + EKF2_OF_DELAY: + decimal: 1 + default: 20 + description: + long: Assumes measurement is timestamped at trailing edge of integration period + short: Optical flow measurement delay relative to IMU measurements + max: 300 + min: 0 + reboot_required: true + type: float + unit: ms + volatile: false + EKF2_OF_GATE: + decimal: 1 + default: 3.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for optical flow fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_OF_N_MAX: + decimal: 2 + default: 0.5 + description: + long: '(when it''s reported quality metric is at the minimum set by EKF2_OF_QMIN). The following condition must be met: EKF2_OF_N_MAXN >= EKF2_OF_N_MIN' + short: Measurement noise for the optical flow sensor + min: 0.05 + type: float + unit: rad/s + volatile: false + EKF2_OF_N_MIN: + decimal: 2 + default: 0.15 + description: + short: Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum + min: 0.05 + type: float + unit: rad/s + volatile: false + EKF2_OF_POS_X: + decimal: 3 + default: 0.0 + description: + short: X position of optical flow focal point in body frame (forward axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_OF_POS_Y: + decimal: 3 + default: 0.0 + description: + short: Y position of optical flow focal point in body frame (right axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_OF_POS_Z: + decimal: 3 + default: 0.0 + description: + short: Z position of optical flow focal point in body frame (down axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_OF_QMIN: + default: 1 + description: + short: Optical Flow data will only be used if the sensor reports a quality metric >= EKF2_OF_QMIN + max: 255 + min: 0 + type: int32 + volatile: false + EKF2_PCOEF_XN: + decimal: 2 + default: 0.0 + description: + long: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. + short: Static pressure position error coefficient for the negative X axis + max: 0.5 + min: -0.5 + type: float + volatile: false + EKF2_PCOEF_XP: + decimal: 2 + default: 0.0 + description: + long: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number. + short: Static pressure position error coefficient for the positive X axis + max: 0.5 + min: -0.5 + type: float + volatile: false + EKF2_PCOEF_YN: + decimal: 2 + default: 0.0 + description: + long: This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number. + short: Pressure position error coefficient for the negative Y axis + max: 0.5 + min: -0.5 + type: float + volatile: false + EKF2_PCOEF_YP: + decimal: 2 + default: 0.0 + description: + long: This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number. + short: Pressure position error coefficient for the positive Y axis + max: 0.5 + min: -0.5 + type: float + volatile: false + EKF2_PCOEF_Z: + decimal: 2 + default: 0.0 + description: + long: This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis. + short: Static pressure position error coefficient for the Z axis + max: 0.5 + min: -0.5 + type: float + volatile: false + EKF2_PREDICT_US: + default: 10000 + description: + long: EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update. + short: EKF prediction period + max: 20000 + min: 1000 + type: int32 + unit: us + volatile: false + EKF2_REQ_EPH: + decimal: 1 + default: 3.0 + description: + short: Required EPH to use GPS + max: 100 + min: 2 + type: float + unit: m + volatile: false + EKF2_REQ_EPV: + decimal: 1 + default: 5.0 + description: + short: Required EPV to use GPS + max: 100 + min: 2 + type: float + unit: m + volatile: false + EKF2_REQ_GPS_H: + decimal: 1 + default: 10.0 + description: + long: Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle. + short: Required GPS health time on startup + min: 0.1 + reboot_required: true + type: float + unit: s + volatile: false + EKF2_REQ_HDRIFT: + decimal: 2 + default: 0.1 + description: + short: Maximum horizontal drift speed to use GPS + max: 1.0 + min: 0.1 + type: float + unit: m/s + volatile: false + EKF2_REQ_NSATS: + default: 6 + description: + short: Required satellite count to use GPS + max: 12 + min: 4 + type: int32 + volatile: false + EKF2_REQ_PDOP: + decimal: 1 + default: 2.5 + description: + short: Maximum PDOP to use GPS + max: 5.0 + min: 1.5 + type: float + volatile: false + EKF2_REQ_SACC: + decimal: 2 + default: 0.5 + description: + short: Required speed accuracy to use GPS + max: 5.0 + min: 0.5 + type: float + unit: m/s + volatile: false + EKF2_REQ_VDRIFT: + decimal: 2 + default: 0.2 + description: + short: Maximum vertical drift speed to use GPS + max: 1.5 + min: 0.1 + type: float + unit: m/s + volatile: false + EKF2_RNG_AID: + default: 1 + description: + long: If this parameter is enabled then the estimator will make use of the range finder measurements to estimate it's height even if range sensor is not the primary height source. It will only do so if conditions for range measurement fusion are met. This enables the range finder to be used during low speed and low altitude operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX. If vehicle motion causes repeated switching between the primary height sensor and range finder, an offset in the local position origin can accumulate. Also range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. + short: Range sensor aid + type: enum + values: + 0: Range aid disabled + 1: Range aid enabled + volatile: false + EKF2_RNG_A_HMAX: + default: 5.0 + description: + long: If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). + short: Maximum absolute altitude (height above ground level) allowed for range aid mode + max: 10.0 + min: 1.0 + type: float + unit: m + volatile: false + EKF2_RNG_A_IGATE: + default: 1.0 + description: + long: A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode + short: Gate size used for innovation consistency checks for range aid fusion + max: 5.0 + min: 0.1 + type: float + unit: SD + volatile: false + EKF2_RNG_A_VMAX: + default: 1.0 + description: + long: If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). + short: Maximum horizontal velocity allowed for range aid mode + max: 2 + min: 0.1 + type: float + unit: m/s + volatile: false + EKF2_RNG_DELAY: + decimal: 1 + default: 5 + description: + short: Range finder measurement delay relative to IMU measurements + max: 300 + min: 0 + reboot_required: true + type: float + unit: ms + volatile: false + EKF2_RNG_GATE: + decimal: 1 + default: 5.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for range finder fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_RNG_K_GATE: + default: 1.0 + description: + long: 'To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.' + short: Gate size used for range finder kinematic consistency check + max: 5.0 + min: 0.1 + type: float + unit: SD + volatile: false + EKF2_RNG_NOISE: + decimal: 2 + default: 0.1 + description: + short: Measurement noise for range finder fusion + min: 0.01 + type: float + unit: m + volatile: false + EKF2_RNG_PITCH: + decimal: 3 + default: 0.0 + description: + short: Range sensor pitch offset + max: 0.75 + min: -0.75 + type: float + unit: rad + volatile: false + EKF2_RNG_POS_X: + decimal: 3 + default: 0.0 + description: + short: X position of range finder origin in body frame (forward axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_RNG_POS_Y: + decimal: 3 + default: 0.0 + description: + short: Y position of range finder origin in body frame (right axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_RNG_POS_Z: + decimal: 3 + default: 0.0 + description: + short: Z position of range finder origin in body frame (down axis with origin relative to vehicle centre of gravity) + type: float + unit: m + volatile: false + EKF2_RNG_QLTY_T: + default: 1.0 + description: + short: Range finder signal quality validation duration. + long: Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s) + max: 5 + min: 0.1 + type: float + unit: s + volatile: false + EKF2_RNG_SFE: + default: 0.05 + description: + long: Specifies the increase in range finder noise with range. + short: Range finder range dependant noise scaler + max: 0.2 + min: 0.0 + type: float + unit: m/m + volatile: false + EKF2_SYNT_MAG_Z: + default: 0 + description: + long: Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ingored instead of fusing the synthetic value. + short: Enable synthetic magnetometer Z component measurement + type: boolean + volatile: false + EKF2_TAS_GATE: + decimal: 1 + default: 3.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for TAS fusion + min: 1.0 + type: float + unit: SD + volatile: false + EKF2_TAU_POS: + decimal: 2 + default: 0.25 + description: + short: Time constant of the position output prediction and smoothing filter. + long: Controls how tightly the output track the EKF states + max: 1.0 + min: 0.1 + type: float + unit: s + volatile: false + EKF2_TAU_VEL: + decimal: 2 + default: 0.25 + description: + short: Time constant of the velocity output prediction and smoothing filter + max: 1.0 + type: float + unit: s + volatile: false + EKF2_TERR_GRAD: + decimal: 2 + default: 0.5 + description: + short: Magnitude of terrain gradient + min: 0.0 + type: float + unit: m/m + volatile: false + EKF2_TERR_MASK: + bit: + 0: use range finder + 1: use optical flow + default: 3 + description: + long: 'Set bits in the following positions to enable: 0 : Set to true to use range finder data if available 1 : Set to true to use optical flow data if available' + short: Integer bitmask controlling fusion sources of the terrain estimator + max: 3 + min: 0 + type: bitmask + volatile: false + EKF2_TERR_NOISE: + decimal: 1 + default: 5.0 + description: + short: Terrain altitude process noise - accounts for instability in vehicle height estimate + min: 0.5 + type: float + unit: m/s + volatile: false + EKF2_WIND_NSD: + decimal: 3 + default: 0.01 + description: + long: When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. + short: Process noise spectral density for wind velocity prediction + max: 1.0 + min: 0.0 + type: float + unit: m/s^2/sqrt(Hz) + volatile: false + EKF2_MULTI_IMU: + default: 0 + description: + long: Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0. + short: Multi-EKF IMUs + max: 4 + min: 0 + reboot_required: true + type: int32 + volatile: false + EKF2_MULTI_MAG: + default: 0 + description: + long: Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0. + short: Multi-EKF Magnetometers + max: 4 + min: 0 + reboot_required: true + type: int32 + volatile: false + EKF2_SEL_ERR_RED: + default: 0.2 + description: + long: EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced. + short: Selector error reduce threshold + type: float + volatile: false + EKF2_SEL_IMU_ACC: + default: 1.0 + description: + long: EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error. + short: Selector acceleration threshold + type: float + unit: m/s^2 + volatile: false + EKF2_SEL_IMU_ANG: + default: 15.0 + description: + long: EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty. + short: Selector angular threshold + type: float + unit: deg + volatile: false + EKF2_SEL_IMU_RAT: + default: 7.0 + description: + long: EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error. + short: Selector angular rate threshold + type: float + unit: deg/s + volatile: false + EKF2_SEL_IMU_VEL: + default: 2.0 + description: + long: EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty. + short: Selector angular threshold + type: float + unit: m/s + volatile: false + EKF2_MAG_DECL: + category: System + decimal: 1 + default: 0 + description: + short: Magnetic declination + type: float + unit: deg + volatile: true + group: EKF2 diff --git a/src/modules/events/CMakeLists.txt b/src/modules/events/CMakeLists.txt index 8c54833d4ee6..f9f8e5ce8466 100644 --- a/src/modules/events/CMakeLists.txt +++ b/src/modules/events/CMakeLists.txt @@ -40,4 +40,6 @@ px4_add_module( send_event.cpp set_leds.cpp status_display.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/modules/events/events_params.c b/src/modules/events/events_params.c deleted file mode 100644 index d9336bf32d5f..000000000000 --- a/src/modules/events/events_params.c +++ /dev/null @@ -1,71 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file events_params.c - * - * Parameters defined by the events module. - */ - -#include -#include - -/** - * Status Display - * - * Enable/disable event task for displaying the vehicle status using arm-mounted - * LEDs. When enabled and if the vehicle supports it, LEDs will flash - * indicating various vehicle status changes. Currently PX4 has not implemented - * any specific status events. - * - - * - * @group Events - * @boolean - * @reboot_required true - */ -PARAM_DEFINE_INT32(EV_TSK_STAT_DIS, 0); - -/** - * RC Loss Alarm - * - * Enable/disable event task for RC Loss. When enabled, an alarm tune will be - * played via buzzer or ESCs, if supported. The alarm will sound after a disarm, - * if the vehicle was previously armed and only if the vehicle had RC signal at - * some point. Particularly useful for locating crashed drones without a GPS - * sensor. - * - * @group Events - * @boolean - * @reboot_required true - */ -PARAM_DEFINE_INT32(EV_TSK_RC_LOSS, 0); diff --git a/src/modules/events/module.yaml b/src/modules/events/module.yaml new file mode 100644 index 000000000000..1c5ea7eeadaf --- /dev/null +++ b/src/modules/events/module.yaml @@ -0,0 +1,27 @@ +module_name: events +parameters: +- definitions: + EV_TSK_RC_LOSS: + default: 0 + description: + long: Enable/disable event task for RC Loss. When enabled, an alarm tune will + be played via buzzer or ESCs, if supported. The alarm will sound after a + disarm, if the vehicle was previously armed and only if the vehicle had + RC signal at some point. Particularly useful for locating crashed drones + without a GPS sensor. + short: RC Loss Alarm + reboot_required: true + type: boolean + volatile: false + EV_TSK_STAT_DIS: + default: 0 + description: + long: Enable/disable event task for displaying the vehicle status using arm-mounted + LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating + various vehicle status changes. Currently PX4 has not implemented any specific + status events. - + short: Status Display + reboot_required: true + type: boolean + volatile: false + group: Events diff --git a/src/modules/flight_mode_manager/CMakeLists.txt b/src/modules/flight_mode_manager/CMakeLists.txt index f8b495e29fe9..f6947294a870 100644 --- a/src/modules/flight_mode_manager/CMakeLists.txt +++ b/src/modules/flight_mode_manager/CMakeLists.txt @@ -115,6 +115,8 @@ px4_add_module( ${CMAKE_CURRENT_BINARY_DIR}/FlightTasks_generated.hpp ${CMAKE_CURRENT_BINARY_DIR}/FlightTasks_generated.cpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue WeatherVane diff --git a/src/modules/flight_mode_manager/flight_mode_manager_params.c b/src/modules/flight_mode_manager/flight_mode_manager_params.c deleted file mode 100644 index cfe2f760f709..000000000000 --- a/src/modules/flight_mode_manager/flight_mode_manager_params.c +++ /dev/null @@ -1,36 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file flight_mode_manager_params.c - */ diff --git a/src/modules/flight_mode_manager/module.yaml b/src/modules/flight_mode_manager/module.yaml new file mode 100644 index 000000000000..f76d691699d1 --- /dev/null +++ b/src/modules/flight_mode_manager/module.yaml @@ -0,0 +1,62 @@ +module_name: flight_mode_manager +parameters: + - definitions: + FLW_TGT_ALT_M: + default: 0 + description: + long: Maintain altitude or track target's altitude. When maintaining the altitude, the drone can crash into terrain when the target moves uphill. When tracking the target's altitude, the follow altitude NAV_MIN_FT_HT should be high enough to prevent terrain collisions due to GPS inaccuracies of the target. + short: Altitude control mode + type: enum + values: + 0: '2D Tracking: Maintain constant altitude relative to home and track XY position only' + 1: '2D + Terrain: Mantain constant altitude relative to terrain below and track XY position' + 2: '3D Tracking: Track target''s altitude (be aware that GPS altitude bias usually makes this useless)' + volatile: false + FLW_TGT_DST: + default: 8.0 + description: + long: The distance in meters to follow the target at + short: Distance to follow target from + min: 1.0 + type: float + unit: m + volatile: false + FLW_TGT_FA: + default: 180.0 + description: + long: 'Angle to follow the target from. 0.0 Equals straight in front of the target''s course (direction of motion) and the angle increases in clockwise direction, meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees Note: When the user force sets the angle out of the min/max range, it will be wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.' + short: Follow Angle setting in degrees + max: 180.0 + min: -180.0 + type: float + volatile: false + FLW_TGT_HT: + default: 8.0 + description: + long: Following height above the target + short: Follow target height + min: 8.0 + type: float + unit: m + volatile: false + FLW_TGT_MAX_VEL: + decimal: 1 + default: 5.0 + description: + long: This is the maximum tangential velocity the drone will circle around the target whenever an orbit angle setpoint changes. Higher value means more aggressive follow behavior. + short: Maximum tangential velocity setting for generating the follow orbit trajectory + max: 20.0 + min: 0.0 + type: float + volatile: false + FLW_TGT_RS: + decimal: 2 + default: 0.1 + description: + long: lower values increase the responsiveness to changing position, but also ignore less noise + short: Responsiveness to target movement in Target Estimator + max: 1.0 + min: 0.0 + type: float + volatile: false + group: Follow target diff --git a/src/modules/flight_mode_manager/tasks/AutoFollowTarget/follow_target_params.c b/src/modules/flight_mode_manager/tasks/AutoFollowTarget/follow_target_params.c deleted file mode 100644 index 2336d323e012..000000000000 --- a/src/modules/flight_mode_manager/tasks/AutoFollowTarget/follow_target_params.c +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2016-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file follow_target_params.c - * - * Parameters for follow target mode - * - * @author Jimmy Johnson - * @author Junwoo Hwang - */ - -/** - * Responsiveness to target movement in Target Estimator - * - * lower values increase the responsiveness to changing position, but also ignore less noise - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @group Follow target - */ -PARAM_DEFINE_FLOAT(FLW_TGT_RS, 0.1f); - -/** - * Follow target height - * - * Following height above the target - * - * @unit m - * @min 8.0 - * @group Follow target - */ -PARAM_DEFINE_FLOAT(FLW_TGT_HT, 8.0f); - -/** - * Distance to follow target from - * - * The distance in meters to follow the target at - * - * @unit m - * @min 1.0 - * @group Follow target - */ -PARAM_DEFINE_FLOAT(FLW_TGT_DST, 8.0f); - -/** - * Follow Angle setting in degrees - * - * Angle to follow the target from. 0.0 Equals straight in front of the target's - * course (direction of motion) and the angle increases in clockwise direction, - * meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees - * - * Note: When the user force sets the angle out of the min/max range, it will be - * wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range. - * - * @min -180.0 - * @max 180.0 - * @group Follow target - */ -PARAM_DEFINE_FLOAT(FLW_TGT_FA, 180.0f); - -/** - * Altitude control mode - * - * Maintain altitude or track target's altitude. When maintaining the altitude, - * the drone can crash into terrain when the target moves uphill. When tracking - * the target's altitude, the follow altitude NAV_MIN_FT_HT should be high enough - * to prevent terrain collisions due to GPS inaccuracies of the target. - * - * @value 0 2D Tracking: Maintain constant altitude relative to home and track XY position only - * @value 1 2D + Terrain: Mantain constant altitude relative to terrain below and track XY position - * @value 2 3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless) - * @group Follow target - */ -PARAM_DEFINE_INT32(FLW_TGT_ALT_M, 0); - -/** - * Maximum tangential velocity setting for generating the follow orbit trajectory - * - * This is the maximum tangential velocity the drone will circle around the target whenever - * an orbit angle setpoint changes. Higher value means more aggressive follow behavior. - * - * @min 0.0 - * @max 20.0 - * @decimal 1 - * @group Follow target - */ -PARAM_DEFINE_FLOAT(FLW_TGT_MAX_VEL, 5.0f); diff --git a/src/modules/fw_att_control/CMakeLists.txt b/src/modules/fw_att_control/CMakeLists.txt index 2cfa1435ba8d..76ac4dcddd81 100644 --- a/src/modules/fw_att_control/CMakeLists.txt +++ b/src/modules/fw_att_control/CMakeLists.txt @@ -42,6 +42,8 @@ px4_add_module( ecl_roll_controller.cpp ecl_wheel_controller.cpp ecl_yaw_controller.cpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue SlewRate diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c deleted file mode 100644 index f99e5cbe6a4d..000000000000 --- a/src/modules/fw_att_control/fw_att_control_params.c +++ /dev/null @@ -1,764 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file fw_att_control_params.c - * - * Parameters defined by the fixed-wing attitude control task - * - * @author Lorenz Meier - * @author Thomas Gubler - */ - -/* - * Controller parameters, accessible via MAVLink - * - */ - -/** - * Attitude Roll Time Constant - * - * This defines the latency between a roll step input and the achieved setpoint - * (inverse to a P gain). Half a second is a good start value and fits for - * most average systems. Smaller systems may require smaller values, but as - * this will wear out servos faster, the value should only be decreased as - * needed. - * - * @unit s - * @min 0.4 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_R_TC, 0.4f); - -/** - * Attitude pitch time constant - * - * This defines the latency between a pitch step input and the achieved setpoint - * (inverse to a P gain). Half a second is a good start value and fits for - * most average systems. Smaller systems may require smaller values, but as - * this will wear out servos faster, the value should only be decreased as - * needed. - * - * @unit s - * @min 0.2 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_P_TC, 0.4f); - -/** - * Pitch rate proportional gain. - * - * This defines how much the elevator input will be commanded depending on the - * current body angular rate error. - * - * @unit %/rad/s - * @min 0.0 - * @max 1.0 - * @decimal 3 - * @increment 0.005 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_PR_P, 0.08f); - -/** - * Pitch rate integrator gain. - * - * This gain defines how much control response will result out of a steady - * state error. It trims any constant error. - * - * @unit %/rad - * @min 0.0 - * @max 0.5 - * @decimal 3 - * @increment 0.005 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_PR_I, 0.1f); - -/** - * Maximum positive / up pitch rate. - * - * This limits the maximum pitch up angular rate the controller will output (in - * degrees per second). - * - * @unit deg/s - * @min 0.0 - * @max 90.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 60.0f); - -/** - * Maximum negative / down pitch rate. - * - * This limits the maximum pitch down up angular rate the controller will - * output (in degrees per second). - * - * @unit deg/s - * @min 0.0 - * @max 90.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 60.0f); - -/** - * Pitch rate integrator limit - * - * The portion of the integrator part in the control surface deflection is - * limited to this value - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.4f); - -/** - * Roll rate proportional Gain - * - * This defines how much the aileron input will be commanded depending on the - * current body angular rate error. - * - * @unit %/rad/s - * @min 0.0 - * @max 1.0 - * @decimal 3 - * @increment 0.005 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_RR_P, 0.05f); - -/** - * Roll rate integrator Gain - * - * This gain defines how much control response will result out of a steady - * state error. It trims any constant error. - * - * @unit %/rad - * @min 0.0 - * @max 0.2 - * @decimal 3 - * @increment 0.005 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_RR_I, 0.1f); - -/** - * Roll integrator anti-windup - * - * The portion of the integrator part in the control surface deflection is limited to this value. - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_RR_IMAX, 0.2f); - -/** - * Maximum roll rate - * - * This limits the maximum roll rate the controller will output (in degrees per - * second). - * - * @unit deg/s - * @min 0.0 - * @max 90.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_R_RMAX, 70.0f); - -/** - * Yaw rate proportional gain - * - * This defines how much the rudder input will be commanded depending on the - * current body angular rate error. - * - * @unit %/rad/s - * @min 0.0 - * @max 1.0 - * @decimal 3 - * @increment 0.005 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_YR_P, 0.05f); - -/** - * Yaw rate integrator gain - * - * This gain defines how much control response will result out of a steady - * state error. It trims any constant error. - * - * @unit %/rad - * @min 0.0 - * @max 50.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_YR_I, 0.1f); - -/** - * Yaw rate integrator limit - * - * The portion of the integrator part in the control surface deflection is - * limited to this value - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_YR_IMAX, 0.2f); - -/** - * Maximum yaw rate - * - * This limits the maximum yaw rate the controller will output (in degrees per - * second). - * - * @unit deg/s - * @min 0.0 - * @max 90.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_Y_RMAX, 50.0f); - -/** - * Roll control to yaw control feedforward gain. - * - * This gain can be used to counteract the "adverse yaw" effect for fixed wings. - * When the plane enters a roll it will tend to yaw the nose out of the turn. - * This gain enables the use of a yaw actuator (rudder, airbrakes, ...) to counteract - * this effect. - * - * @min 0.0 - * @decimal 1 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_RLL_TO_YAW_FF, 0.0f); - -/** - * Enable wheel steering controller - * - * @boolean - * @group FW Attitude Control - */ -PARAM_DEFINE_INT32(FW_W_EN, 0); - - -/** - * Wheel steering rate proportional gain - * - * This defines how much the wheel steering input will be commanded depending on the - * current body angular rate error. - * - * @unit %/rad/s - * @min 0.0 - * @max 1.0 - * @decimal 3 - * @increment 0.005 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_WR_P, 0.5f); - -/** - * Wheel steering rate integrator gain - * - * This gain defines how much control response will result out of a steady - * state error. It trims any constant error. - * - * @unit %/rad - * @min 0.0 - * @max 0.5 - * @decimal 3 - * @increment 0.005 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_WR_I, 0.1f); - -/** - * Wheel steering rate integrator limit - * - * The portion of the integrator part in the control surface deflection is - * limited to this value - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_WR_IMAX, 1.0f); - -/** - * Maximum wheel steering rate - * - * This limits the maximum wheel steering rate the controller will output (in degrees per - * second). - * - * @unit deg/s - * @min 0.0 - * @max 90.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_W_RMAX, 30.0f); - -/** - * Roll rate feed forward - * - * Direct feed forward from rate setpoint to control surface output. Use this - * to obtain a tigher response of the controller without introducing - * noise amplification. - * - * @unit %/rad/s - * @min 0.0 - * @max 10.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_RR_FF, 0.5f); - -/** - * Pitch rate feed forward - * - * Direct feed forward from rate setpoint to control surface output - * - * @unit %/rad/s - * @min 0.0 - * @max 10.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_PR_FF, 0.5f); - -/** - * Yaw rate feed forward - * - * Direct feed forward from rate setpoint to control surface output - * - * @unit %/rad/s - * @min 0.0 - * @max 10.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_YR_FF, 0.3f); - -/** - * Wheel steering rate feed forward - * - * Direct feed forward from rate setpoint to control surface output - * - * @unit %/rad/s - * @min 0.0 - * @max 10.0 - * @decimal 2 - * @increment 0.05 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_WR_FF, 0.2f); - -/** - * Pitch setpoint offset (pitch at level flight) - * - * An airframe specific offset of the pitch setpoint in degrees, the value is - * added to the pitch setpoint and should correspond to the pitch at - * typical cruise speed of the airframe. - * - * @unit deg - * @min -90.0 - * @max 90.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_PSP_OFF, 0.0f); - -/** - * Maximum manual roll angle - * - * Maximum manual roll angle setpoint (positive & negative) in manual attitude-only stabilized mode - * - * @unit deg - * @min 0.0 - * @max 90.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_MAN_R_MAX, 45.0f); - -/** - * Maximum manual pitch angle - * - * Maximum manual pitch angle setpoint (positive & negative) in manual attitude-only stabilized mode - * - * @unit deg - * @min 0.0 - * @max 90.0 - * @decimal 1 - * @increment 0.5 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_MAN_P_MAX, 45.0f); - -/** - * Flaps setting during take-off - * - * Sets a fraction of full flaps during take-off. - * Also applies to flaperons if enabled in the mixer/allocation. - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_FLAPS_TO_SCL, 0.0f); - -/** - * Flaps setting during landing - * - * Sets a fraction of full flaps during landing. - * Also applies to flaperons if enabled in the mixer/allocation. - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_FLAPS_LND_SCL, 1.0f); - -/** - * Airspeed mode - * - * For small wings or VTOL without airspeed sensor this parameter can be used to - * enable flying without an airspeed reading - * - * @value 0 Normal (use airspeed if available) - * @value 1 Airspeed disabled - * @group FW Attitude Control - */ -PARAM_DEFINE_INT32(FW_ARSP_MODE, 0); - -/** - * Enable airspeed scaling - * - * This enables a logic that automatically adjusts the output of the rate controller to take - * into account the real torque produced by an aerodynamic control surface given - * the current deviation from the trim airspeed (FW_AIRSPD_TRIM). - * - * Enable when using aerodynamic control surfaces (e.g.: plane) - * Disable when using rotor wings (e.g.: autogyro) - * - * @boolean - * @group FW Attitude Control - */ -PARAM_DEFINE_INT32(FW_ARSP_SCALE_EN, 1); - -/** - * Manual roll scale - * - * Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows - * to adjust the throws of the control surfaces. - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_MAN_R_SC, 1.0f); - -/** - * Manual pitch scale - * - * Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows - * to adjust the throws of the control surfaces. - * - * @unit norm - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_MAN_P_SC, 1.0f); - -/** - * Manual yaw scale - * - * Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows - * to adjust the throws of the control surfaces. - * - * @unit norm - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_MAN_Y_SC, 1.0f); - -/** - * Whether to scale throttle by battery power level - * - * This compensates for voltage drop of the battery over time by attempting to - * normalize performance across the operating range of the battery. The fixed wing - * should constantly behave as if it was fully charged with reduced max thrust - * at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, - * it will still be 0.5 at 60% battery. - * - * @boolean - * @group FW Attitude Control - */ -PARAM_DEFINE_INT32(FW_BAT_SCALE_EN, 0); - -/** - * Acro body x max rate. - * - * This is the rate the controller is trying to achieve if the user applies full roll - * stick input in acro mode. - * - * @min 45 - * @max 720 - * @unit deg - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_ACRO_X_MAX, 90); - -/** - * Acro body y max rate. - * - * This is the body y rate the controller is trying to achieve if the user applies full pitch - * stick input in acro mode. - * - * @min 45 - * @max 720 - * @unit deg - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_ACRO_Y_MAX, 90); - -/** - * Acro body z max rate. - * - * This is the body z rate the controller is trying to achieve if the user applies full yaw - * stick input in acro mode. - * - * @min 10 - * @max 180 - * @unit deg - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_ACRO_Z_MAX, 45); - -/** -* Roll trim increment at minimum airspeed -* -* This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_R_VMIN, 0.0f); - -/** -* Pitch trim increment at minimum airspeed -* -* This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_P_VMIN, 0.0f); - -/** -* Yaw trim increment at minimum airspeed -* -* This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_Y_VMIN, 0.0f); - -/** -* Roll trim increment at maximum airspeed -* -* This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_R_VMAX, 0.0f); - -/** -* Pitch trim increment at maximum airspeed -* -* This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_P_VMAX, 0.0f); - -/** -* Yaw trim increment at maximum airspeed -* -* This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_Y_VMAX, 0.0f); - -/** - * Roll trim increment for flaps configuration - * - * This increment is added to TRIM_ROLL whenever flaps are fully deployed. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_R_FLPS, 0.0f); - -/** - * Pitch trim increment for flaps configuration - * - * This increment is added to the pitch trim whenever flaps are fully deployed. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_P_FLPS, 0.0f); - -/** - * Pitch trim increment for spoiler configuration - * - * This increment is added to the pitch trim whenever spoilers are fully deployed. - * - * @group FW Attitude Control - * @min -0.25 - * @max 0.25 - * @decimal 2 - * @increment 0.01 - */ -PARAM_DEFINE_FLOAT(FW_DTRIM_P_SPOIL, 0.f); - -/** - * Spoiler landing setting - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_SPOILERS_LND, 0.f); - -/** - * Spoiler descend setting - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW Attitude Control - */ -PARAM_DEFINE_FLOAT(FW_SPOILERS_DESC, 0.f); - -/** - * Spoiler input in manual flight - * - * Chose source for manual setting of spoilers in manual flight modes. - * - * @value 0 Disabled - * @value 1 Flaps channel - * @value 2 Aux1 - * @group FW Attitude Control - */ -PARAM_DEFINE_INT32(FW_SPOILERS_MAN, 0); diff --git a/src/modules/fw_att_control/module.yaml b/src/modules/fw_att_control/module.yaml new file mode 100644 index 000000000000..d5d69b611277 --- /dev/null +++ b/src/modules/fw_att_control/module.yaml @@ -0,0 +1,572 @@ +module_name: fw_att_control +parameters: + - definitions: + FW_ACRO_X_MAX: + default: 90 + description: + long: This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode. + short: Acro body x max rate + max: 720 + min: 45 + type: float + unit: deg + volatile: false + FW_ACRO_Y_MAX: + default: 90 + description: + long: This is the body y rate the controller is trying to achieve if the user applies full pitch stick input in acro mode. + short: Acro body y max rate + max: 720 + min: 45 + type: float + unit: deg + volatile: false + FW_ACRO_Z_MAX: + default: 45 + description: + long: This is the body z rate the controller is trying to achieve if the user applies full yaw stick input in acro mode. + short: Acro body z max rate + max: 180 + min: 10 + type: float + unit: deg + volatile: false + FW_ARSP_MODE: + default: 0 + description: + long: For small wings or VTOL without airspeed sensor this parameter can be used to enable flying without an airspeed reading + short: Airspeed mode + type: enum + values: + 0: Normal (use airspeed if available) + 1: Airspeed disabled + volatile: false + FW_ARSP_SCALE_EN: + default: 1 + description: + long: 'This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)' + short: Enable airspeed scaling + type: boolean + volatile: false + FW_BAT_SCALE_EN: + default: 0 + description: + long: This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. + short: Whether to scale throttle by battery power level + type: boolean + volatile: false + FW_DTRIM_P_FLPS: + decimal: 2 + default: 0.0 + description: + long: This increment is added to the pitch trim whenever flaps are fully deployed. + short: Pitch trim increment for flaps configuration + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_DTRIM_P_SPOIL: + decimal: 2 + default: 0.0 + description: + long: This increment is added to the pitch trim whenever spoilers are fully deployed. + short: Pitch trim increment for spoiler configuration + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_DTRIM_P_VMAX: + decimal: 2 + default: 0.0 + description: + long: This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX. + short: Pitch trim increment at maximum airspeed + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_DTRIM_P_VMIN: + decimal: 2 + default: 0.0 + description: + long: This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN. + short: Pitch trim increment at minimum airspeed + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_DTRIM_R_FLPS: + decimal: 2 + default: 0.0 + description: + long: This increment is added to TRIM_ROLL whenever flaps are fully deployed. + short: Roll trim increment for flaps configuration + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_DTRIM_R_VMAX: + decimal: 2 + default: 0.0 + description: + long: This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX. + short: Roll trim increment at maximum airspeed + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_DTRIM_R_VMIN: + decimal: 2 + default: 0.0 + description: + long: This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN. + short: Roll trim increment at minimum airspeed + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_DTRIM_Y_VMAX: + decimal: 2 + default: 0.0 + description: + long: This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX. + short: Yaw trim increment at maximum airspeed + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_DTRIM_Y_VMIN: + decimal: 2 + default: 0.0 + description: + long: This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN. + short: Yaw trim increment at minimum airspeed + increment: 0.01 + max: 0.25 + min: -0.25 + type: float + volatile: false + FW_FLAPS_LND_SCL: + decimal: 2 + default: 1.0 + description: + long: Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation. + short: Flaps setting during landing + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FW_FLAPS_TO_SCL: + decimal: 2 + default: 0.0 + description: + long: Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation. + short: Flaps setting during take-off + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FW_MAN_P_MAX: + decimal: 1 + default: 45.0 + description: + long: Maximum manual pitch angle setpoint (positive & negative) in manual attitude-only stabilized mode + short: Maximum manual pitch angle + increment: 0.5 + max: 90.0 + min: 0.0 + type: float + unit: deg + volatile: false + FW_MAN_P_SC: + decimal: 2 + default: 1.0 + description: + long: Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. + short: Manual pitch scale + increment: 0.01 + min: 0.0 + type: float + unit: norm + volatile: false + FW_MAN_R_MAX: + decimal: 1 + default: 45.0 + description: + long: Maximum manual roll angle setpoint (positive & negative) in manual attitude-only stabilized mode + short: Maximum manual roll angle + increment: 0.5 + max: 90.0 + min: 0.0 + type: float + unit: deg + volatile: false + FW_MAN_R_SC: + decimal: 2 + default: 1.0 + description: + long: Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. + short: Manual roll scale + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FW_MAN_Y_SC: + decimal: 2 + default: 1.0 + description: + long: Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. + short: Manual yaw scale + increment: 0.01 + min: 0.0 + type: float + unit: norm + volatile: false + FW_PR_FF: + decimal: 2 + default: 0.5 + description: + long: Direct feed forward from rate setpoint to control surface output + short: Pitch rate feed forward + increment: 0.05 + max: 10.0 + min: 0.0 + type: float + unit: '%/rad/s' + volatile: false + FW_PR_I: + decimal: 3 + default: 0.1 + description: + long: This gain defines how much control response will result out of a steady state error. It trims any constant error. + short: Pitch rate integrator gain + increment: 0.005 + max: 0.5 + min: 0.0 + type: float + unit: '%/rad' + volatile: false + FW_PR_IMAX: + decimal: 2 + default: 0.4 + description: + long: The portion of the integrator part in the control surface deflection is limited to this value + short: Pitch rate integrator limit + increment: 0.05 + max: 1.0 + min: 0.0 + type: float + volatile: false + FW_PR_P: + decimal: 3 + default: 0.08 + description: + long: This defines how much the elevator input will be commanded depending on the current body angular rate error. + short: Pitch rate proportional gain + increment: 0.005 + max: 1.0 + min: 0.0 + type: float + unit: '%/rad/s' + volatile: false + FW_PSP_OFF: + decimal: 1 + default: 0.0 + description: + long: An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe. + short: Pitch setpoint offset (pitch at level flight) + increment: 0.5 + max: 90.0 + min: -90.0 + type: float + unit: deg + volatile: false + FW_P_RMAX_NEG: + decimal: 1 + default: 60.0 + description: + long: This limits the maximum pitch down up angular rate the controller will output (in degrees per second). + short: Maximum negative / down pitch rate + increment: 0.5 + max: 90.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + FW_P_RMAX_POS: + decimal: 1 + default: 60.0 + description: + long: This limits the maximum pitch up angular rate the controller will output (in degrees per second). + short: Maximum positive / up pitch rate + increment: 0.5 + max: 90.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + FW_P_TC: + decimal: 2 + default: 0.4 + description: + long: This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. + short: Attitude pitch time constant + increment: 0.05 + max: 1.0 + min: 0.2 + type: float + unit: s + volatile: false + FW_RLL_TO_YAW_FF: + decimal: 1 + default: 0.0 + description: + long: This gain can be used to counteract the "adverse yaw" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator (rudder, airbrakes, ...) to counteract this effect. + short: Roll control to yaw control feedforward gain + increment: 0.01 + min: 0.0 + type: float + volatile: false + FW_RR_FF: + decimal: 2 + default: 0.5 + description: + long: Direct feed forward from rate setpoint to control surface output. Use this to obtain a tigher response of the controller without introducing noise amplification. + short: Roll rate feed forward + increment: 0.05 + max: 10.0 + min: 0.0 + type: float + unit: '%/rad/s' + volatile: false + FW_RR_I: + decimal: 3 + default: 0.1 + description: + long: This gain defines how much control response will result out of a steady state error. It trims any constant error. + short: Roll rate integrator Gain + increment: 0.005 + max: 0.2 + min: 0.0 + type: float + unit: '%/rad' + volatile: false + FW_RR_IMAX: + decimal: 2 + default: 0.2 + description: + long: The portion of the integrator part in the control surface deflection is limited to this value. + short: Roll integrator anti-windup + increment: 0.05 + max: 1.0 + min: 0.0 + type: float + volatile: false + FW_RR_P: + decimal: 3 + default: 0.05 + description: + long: This defines how much the aileron input will be commanded depending on the current body angular rate error. + short: Roll rate proportional Gain + increment: 0.005 + max: 1.0 + min: 0.0 + type: float + unit: '%/rad/s' + volatile: false + FW_R_RMAX: + decimal: 1 + default: 70.0 + description: + long: This limits the maximum roll rate the controller will output (in degrees per second). + short: Maximum roll rate + increment: 0.5 + max: 90.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + FW_R_TC: + decimal: 2 + default: 0.4 + description: + long: This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. + short: Attitude Roll Time Constant + increment: 0.05 + max: 1.0 + min: 0.4 + type: float + unit: s + volatile: false + FW_SPOILERS_DESC: + decimal: 2 + default: 0.0 + description: + short: Spoiler descend setting + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FW_SPOILERS_LND: + decimal: 2 + default: 0.0 + description: + short: Spoiler landing setting + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FW_SPOILERS_MAN: + default: 0 + description: + long: Chose source for manual setting of spoilers in manual flight modes. + short: Spoiler input in manual flight + type: enum + values: + 0: Disabled + 1: Flaps channel + 2: Aux1 + volatile: false + FW_WR_FF: + decimal: 2 + default: 0.2 + description: + long: Direct feed forward from rate setpoint to control surface output + short: Wheel steering rate feed forward + increment: 0.05 + max: 10.0 + min: 0.0 + type: float + unit: '%/rad/s' + volatile: false + FW_WR_I: + decimal: 3 + default: 0.1 + description: + long: This gain defines how much control response will result out of a steady state error. It trims any constant error. + short: Wheel steering rate integrator gain + increment: 0.005 + max: 0.5 + min: 0.0 + type: float + unit: '%/rad' + volatile: false + FW_WR_IMAX: + decimal: 2 + default: 1.0 + description: + long: The portion of the integrator part in the control surface deflection is limited to this value + short: Wheel steering rate integrator limit + increment: 0.05 + max: 1.0 + min: 0.0 + type: float + volatile: false + FW_WR_P: + decimal: 3 + default: 0.5 + description: + long: This defines how much the wheel steering input will be commanded depending on the current body angular rate error. + short: Wheel steering rate proportional gain + increment: 0.005 + max: 1.0 + min: 0.0 + type: float + unit: '%/rad/s' + volatile: false + FW_W_EN: + default: 0 + description: + short: Enable wheel steering controller + type: boolean + volatile: false + FW_W_RMAX: + decimal: 1 + default: 30.0 + description: + long: This limits the maximum wheel steering rate the controller will output (in degrees per second). + short: Maximum wheel steering rate + increment: 0.5 + max: 90.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + FW_YR_FF: + decimal: 2 + default: 0.3 + description: + long: Direct feed forward from rate setpoint to control surface output + short: Yaw rate feed forward + increment: 0.05 + max: 10.0 + min: 0.0 + type: float + unit: '%/rad/s' + volatile: false + FW_YR_I: + decimal: 1 + default: 0.1 + description: + long: This gain defines how much control response will result out of a steady state error. It trims any constant error. + short: Yaw rate integrator gain + increment: 0.5 + max: 50.0 + min: 0.0 + type: float + unit: '%/rad' + volatile: false + FW_YR_IMAX: + decimal: 2 + default: 0.2 + description: + long: The portion of the integrator part in the control surface deflection is limited to this value + short: Yaw rate integrator limit + increment: 0.05 + max: 1.0 + min: 0.0 + type: float + volatile: false + FW_YR_P: + decimal: 3 + default: 0.05 + description: + long: This defines how much the rudder input will be commanded depending on the current body angular rate error. + short: Yaw rate proportional gain + increment: 0.005 + max: 1.0 + min: 0.0 + type: float + unit: '%/rad/s' + volatile: false + FW_Y_RMAX: + decimal: 1 + default: 50.0 + description: + long: This limits the maximum yaw rate the controller will output (in degrees per second). + short: Maximum yaw rate + increment: 0.5 + max: 90.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + group: FW Attitude Control diff --git a/src/modules/fw_autotune_attitude_control/CMakeLists.txt b/src/modules/fw_autotune_attitude_control/CMakeLists.txt index 3c898a21acb0..0c499c6eeebd 100644 --- a/src/modules/fw_autotune_attitude_control/CMakeLists.txt +++ b/src/modules/fw_autotune_attitude_control/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( SRCS fw_autotune_attitude_control.cpp fw_autotune_attitude_control.hpp + MODULE_CONFIG + module.yaml DEPENDS hysteresis mathlib diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c deleted file mode 100644 index 3d7b938357a5..000000000000 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control_params.c +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020-2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file fw_autotune_attitude_control_params.c - * - * Parameters used by the attitude auto-tuner - * - * @author Mathieu Bresciani - */ - -/** - * Start the autotuning sequence - * - * WARNING: this will inject steps to the rate controller - * and can be dangerous. Only activate if you know what you - * are doing, and in a safe environment. - * - * Any motion of the remote stick will abord the signal - * injection and reset this parameter - * Best is to perform the identification in position or - * hold mode. - * Increase the amplitude of the injected signal using - * FW_AT_SYSID_AMP for more signal/noise ratio - * - * @boolean - * @group Autotune - */ -PARAM_DEFINE_INT32(FW_AT_START, 0); - -/** - * Amplitude of the injected signal - * - * This parameter scales the signal sent to the - * rate controller during system identification. - * - * @min 0.1 - * @max 6.0 - * @decimal 1 - * @group Autotune - */ -PARAM_DEFINE_FLOAT(FW_AT_SYSID_AMP, 1.0); - -/** - * Controls when to apply the new gains - * - * After the auto-tuning sequence is completed, - * a new set of gains is available and can be applied - * immediately or after landing. - * - * @value 0 Do not apply the new gains (logging only) - * @value 1 Apply the new gains after disarm - * @value 2 Apply the new gains in air - * @group Autotune - */ -PARAM_DEFINE_INT32(FW_AT_APPLY, 2); - -/** - * Tuning axes selection - * - * Defines which axes will be tuned during the auto-tuning sequence - * - * Set bits in the following positions to enable: - * 0 : Roll - * 1 : Pitch - * 2 : Yaw - * - * @bit 0 roll - * @bit 1 pitch - * @bit 2 yaw - * @min 1 - * @max 7 - * @group Autotune - */ -PARAM_DEFINE_INT32(FW_AT_AXES, 3); diff --git a/src/modules/fw_autotune_attitude_control/module.yaml b/src/modules/fw_autotune_attitude_control/module.yaml new file mode 100644 index 000000000000..31fde5a40a61 --- /dev/null +++ b/src/modules/fw_autotune_attitude_control/module.yaml @@ -0,0 +1,45 @@ +module_name: fw_autotune_attitude_control +parameters: + - definitions: + FW_AT_APPLY: + default: 2 + description: + long: After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. + short: Controls when to apply the new gains + type: enum + values: + 0: Do not apply the new gains (logging only) + 1: Apply the new gains after disarm + 2: Apply the new gains in air + volatile: false + FW_AT_AXES: + bit: + 0: roll + 1: pitch + 2: yaw + default: 3 + description: + long: 'Defines which axes will be tuned during the auto-tuning sequence Set bits in the following positions to enable: 0 : Roll 1 : Pitch 2 : Yaw' + short: Tuning axes selection + max: 7 + min: 1 + type: bitmask + volatile: false + FW_AT_START: + default: 0 + description: + long: 'WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abord the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using FW_AT_SYSID_AMP for more signal/noise ratio' + short: Start the autotuning sequence + type: boolean + volatile: false + FW_AT_SYSID_AMP: + decimal: 1 + default: 1.0 + description: + long: This parameter scales the signal sent to the rate controller during system identification. + short: Amplitude of the injected signal + max: 6.0 + min: 0.1 + type: float + volatile: false + group: Autotune diff --git a/src/modules/fw_pos_control_l1/CMakeLists.txt b/src/modules/fw_pos_control_l1/CMakeLists.txt index d7deaa987004..51b27f873a91 100644 --- a/src/modules/fw_pos_control_l1/CMakeLists.txt +++ b/src/modules/fw_pos_control_l1/CMakeLists.txt @@ -40,6 +40,8 @@ px4_add_module( SRCS FixedwingPositionControl.cpp FixedwingPositionControl.hpp + MODULE_CONFIG + module.yaml DEPENDS l1 launchdetection diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c deleted file mode 100644 index 25f39040a34e..000000000000 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ /dev/null @@ -1,1078 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file fw_pos_control_l1_params.c - * - * Parameters defined by the L1 position control task - * - * @author Lorenz Meier - */ - -/* - * Controller parameters, accessible via MAVLink - */ - -/** - * L1 period - * - * Used to determine the L1 gain and controller time constant. This parameter is - * proportional to the L1 distance (which points ahead of the aircraft on the path - * it is following). A value of 18-25 seconds works for most aircraft. Shorten - * slowly during tuning until response is sharp without oscillation. - * - * @unit s - * @min 7.0 - * @max 50.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 20.0f); - -/** - * L1 damping - * - * Damping factor for L1 control. - * - * @min 0.6 - * @max 0.9 - * @decimal 2 - * @increment 0.05 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f); - -/** - * L1 controller roll slew rate limit. - * - * The maxium change in roll angle setpoint per second. - * - * @unit deg/s - * @min 0 - * @increment 1 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_L1_R_SLEW_MAX, 90.0f); - -/** - * Use NPFG as lateral-directional guidance law for fixed-wing vehicles - * - * Replaces L1. - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(FW_USE_NPFG, 0); - -/** - * NPFG period - * - * Period of the NPFG control law. - * - * @unit s - * @min 1.0 - * @max 100.0 - * @decimal 1 - * @increment 0.1 - * @group FW NPFG Control - */ -PARAM_DEFINE_FLOAT(NPFG_PERIOD, 10.0f); - -/** - * NPFG damping ratio - * - * Damping ratio of the NPFG control law. - * - * @min 0.10 - * @max 1.00 - * @decimal 2 - * @increment 0.01 - * @group FW NPFG Control - */ -PARAM_DEFINE_FLOAT(NPFG_DAMPING, 0.7f); - -/** - * Enable automatic lower bound on the NPFG period - * - * Avoids limit cycling from a too aggressively tuned period/damping combination. - * If set to false, also disables the upper bound NPFG_PERIOD_UB. - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(NPFG_LB_PERIOD, 1); - -/** - * Enable automatic upper bound on the NPFG period - * - * Adapts period to maintain track keeping in variable winds and path curvature. - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(NPFG_UB_PERIOD, 1); - -/** - * Enable track keeping excess wind handling logic. - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(NPFG_TRACK_KEEP, 1); - -/** - * Enable minimum forward ground speed maintaining excess wind handling logic - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(NPFG_EN_MIN_GSP, 1); - -/** - * Enable wind excess regulation. - * - * Disabling this parameter further disables all other airspeed incrementation options. - * - * @boolean - * @group FW NPFG Control - */ -PARAM_DEFINE_INT32(NPFG_WIND_REG, 1); - -/** - * Maximum, minimum forward ground speed for track keeping in excess wind - * - * The maximum value of the minimum forward ground speed that may be commanded - * by the track keeping excess wind handling logic. Commanded in full at the normalized - * track error fraction of the track error boundary and reduced to zero on track. - * - * @unit m/s - * @min 0.0 - * @max 10.0 - * @decimal 1 - * @increment 0.5 - * @group FW NPFG Control - */ -PARAM_DEFINE_FLOAT(NPFG_GSP_MAX_TK, 5.0f); - -/** - * Roll time constant - * - * Time constant of roll controller command / response, modeled as first order delay. - * Used to determine lower period bound. Setting zero disables automatic period bounding. - * - * @unit s - * @min 0.00 - * @max 2.00 - * @decimal 2 - * @increment 0.05 - * @group FW NPFG Control - */ -PARAM_DEFINE_FLOAT(NPFG_ROLL_TC, 0.5f); - -/** - * NPFG switch distance multiplier - * - * Multiplied by the track error boundary to determine when the aircraft switches - * to the next waypoint and/or path segment. Should be less than 1. 1/pi (0.32) - * sets the switch distance equivalent to that of the L1 controller. - * - * @min 0.1 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW NPFG Control - */ -PARAM_DEFINE_FLOAT(NPFG_SW_DST_MLT, 0.32f); - -/** - * Period safety factor - * - * Multiplied by period for conservative minimum period bounding (when period lower - * bounding is enabled). 1.0 bounds at marginal stability. - * - * @min 1.0 - * @max 10.0 - * @decimal 1 - * @increment 0.1 - * @group FW NPFG Control - */ -PARAM_DEFINE_FLOAT(NPFG_PERIOD_SF, 1.5f); - -/** - * Trim throttle - * - * This is the throttle setting required to achieve FW_AIRSPD_TRIM during level flight. Most airframes have a value of 0.5-0.7. - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_THR_TRIM, 0.6f); - -/** - * Throttle max slew rate - * - * Maximum slew rate for the commanded throttle - * - * @min 0.0 - * @max 1.0 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); - -/** - * Minimum pitch angle - * - * The minimum pitch angle setpoint for autonomous modes including altitude and position control. - * - * @unit deg - * @min -60.0 - * @max 0.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f); - -/** - * Maximum pitch angle - * - * The maximum pitch angle setpoint for autonomous modes including altitude and position control. - * - * @unit deg - * @min 0.0 - * @max 60.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f); - -/** - * Maximum roll angle - * - * The maximum roll angle setpoint for autonomous modes including altitude and position control. - * - * @unit deg - * @min 35.0 - * @max 65.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f); - -/** - * Throttle limit max - * - * This is the maximum throttle % that can be used by the controller. - * For overpowered aircraft, this should be reduced to a value that - * provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); - -/** - * Throttle limit min - * - * This is the minimum throttle % that can be used by the controller. - * For electric aircraft this will normally be set to zero, but can be set - * to a small non-zero value if a folding prop is fitted to prevent the - * prop from folding and unfolding repeatedly in-flight or to provide - * some aerodynamic drag from a turning prop to improve the descent rate. - * - * For aircraft with internal combustion engine this parameter should be set - * for desired idle rpm. - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); - -/** - * Idle throttle - * - * This is the minimum throttle while on the ground - * - * For aircraft with internal combustion engines, this parameter should be set - * above the desired idle rpm. For electric motors, idle should typically be set - * to zero. - * - * Note that in automatic modes, "landed" conditions will engage idle throttle. - * - * @unit norm - * @min 0.0 - * @max 0.4 - * @decimal 2 - * @increment 0.01 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_THR_IDLE, 0.0f); - -/** - * Climbout Altitude difference - * - * If the altitude error exceeds this parameter, the system will climb out - * with maximum throttle and minimum airspeed until it is closer than this - * distance to the desired altitude. Mostly used for takeoff waypoints / modes. - * Set to 0 to disable climbout mode (not recommended). - * - * @unit m - * @min 0.0 - * @max 150.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 10.0f); - -/** - * Maximum landing slope angle - * - * Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. - * Set this value within the vehicle's performance limits. - * - * @unit deg - * @min 1.0 - * @max 15.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); - -/** - * Minimum pitch during takeoff. - * - * @unit deg - * @min -5.0 - * @max 30.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_TKO_PITCH_MIN, 10.0f); - -/** - * Landing flare altitude (relative to landing altitude) - * - * NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude - * - * @unit m - * @min 0.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_FLALT, 0.5f); - -/** - * Use terrain estimation during landing. This is critical for detecting when to flare, and should be enabled if possible. - * - * NOTE: terrain estimate is currently solely derived from a distance sensor. - * - * If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing - * will be aborted, depending on the criteria set in FW_LND_ABORT. - * - * If disabled, FW_LND_ABORT terrain based criteria are ignored. - * - * @min 0 - * @max 2 - * @value 0 Disable the terrain estimate - * @value 1 Use the terrain estimate to trigger the flare (only) - * @value 2 Calculate landing glide slope relative to the terrain estimate - * @group FW L1 Control - */ -PARAM_DEFINE_INT32(FW_LND_USETER, 1); - -/** - * Early landing configuration deployment - * - * When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated - * on the final approach to landing. When enabled, it is already activated when entering the - * final loiter-down (loiter-to-alt) waypoint before the landing approach. This shifts the (often large) - * altitude and airspeed errors caused by the configuration change away from the ground such that - * these are not so critical. It also gives the controller enough time to adapt to the new - * configuration such that the landing approach starts with a cleaner initial state. - * - * @boolean - * - * @group FW L1 Control - */ -PARAM_DEFINE_INT32(FW_LND_EARLYCFG, 0); - -/** - * Flare, minimum pitch - * - * Minimum pitch during flare, a positive sign means nose up - * Applied once flaring is triggered - * - * @unit deg - * @min 0 - * @max 15.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f); - -/** - * Flare, maximum pitch - * - * Maximum pitch during flare, a positive sign means nose up - * Applied once flaring is triggered - * - * @unit deg - * @min 0 - * @max 45.0 - * @decimal 1 - * @increment 0.5 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f); - -/** - * Min. airspeed scaling factor for landing - * - * Multiplying this factor with the minimum airspeed of the plane - * gives the target airspeed the landing approach. - * FW_AIRSPD_MIN * FW_LND_AIRSPD_SC - * - * @unit norm - * @min 1.0 - * @max 1.5 - * @decimal 2 - * @increment 0.01 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_AIRSPD_SC, 1.3f); - -/** - * Altitude time constant factor for landing - * - * Set this parameter to less than 1.0 to make TECS react faster to altitude errors during - * landing than during normal flight (i.e. giving efficiency and low motor wear at - * high altitudes but control accuracy during landing). During landing, the TECS - * altitude time constant (FW_T_ALT_TC) is multiplied by this value. - * - * @unit - * @min 0.2 - * @max 1.0 - * @increment 0.1 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_THRTC_SC, 1.0f); - - - -/* - * TECS parameters - * - */ - - -/** - * Minimum Airspeed (CAS) - * - * The minimal airspeed (calibrated airspeed) the user is able to command. - * Further, if the airspeed falls below this value, the TECS controller will try to - * increase airspeed more aggressively. - * - * @unit m/s - * @min 0.5 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 10.0f); - -/** - * Maximum Airspeed (CAS) - * - * If the CAS (calibrated airspeed) is above this value, the TECS controller will try to decrease - * airspeed more aggressively. - * - * @unit m/s - * @min 0.5 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 20.0f); - -/** - * Cruise Airspeed (CAS) - * - * The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, - * this is the default airspeed setpoint that the controller will try to achieve if - * no other airspeed setpoint sources are present (e.g. through non-centered RC sticks). - * - * @unit m/s - * @min 0.5 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 15.0f); - -/** - * Stall Airspeed (CAS) - * - * The stall airspeed (calibrated airspeed) of the vehicle. - * It is used for airspeed sensor failure detection and for the control - * surface scaling airspeed limits. - * - * @unit m/s - * @min 0.5 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_AIRSPD_STALL, 7.0f); - -/** - * Maximum climb rate - * - * This is the best climb rate that the aircraft can achieve with - * the throttle set to THR_MAX and the airspeed set to the - * default value. For electric aircraft make sure this number can be - * achieved towards the end of flight when the battery voltage has reduced. - * The setting of this parameter can be checked by commanding a positive - * altitude change of 100m in loiter, RTL or guided mode. If the throttle - * required to climb is close to THR_MAX and the aircraft is maintaining - * airspeed, then this parameter is set correctly. If the airspeed starts - * to reduce, then the parameter is set to high, and if the throttle - * demand required to climb and maintain speed is noticeably less than - * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or - * FW_THR_MAX reduced. - * - * @unit m/s - * @min 1.0 - * @max 15.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f); - -/** - * Minimum descent rate - * - * This is the sink rate of the aircraft with the throttle - * set to THR_MIN and flown at the same airspeed as used - * to measure FW_T_CLMB_MAX. - * - * @unit m/s - * @min 1.0 - * @max 5.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); - -/** - * Maximum descent rate - * - * This sets the maximum descent rate that the controller will use. - * If this value is too large, the aircraft can over-speed on descent. - * This should be set to a value that can be achieved without - * exceeding the lower pitch angle limit and without over-speeding - * the aircraft. - * - * @unit m/s - * @min 1.0 - * @max 15.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); - -/** - * Throttle damping factor - * - * This is the damping gain for the throttle demand loop. - * Increase to add damping to correct for oscillations in speed and height. - * - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @increment 0.1 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.1f); - -/** - * Integrator gain throttle - * - * This is the integrator gain on the throttle part of the control loop. - * Increasing this gain increases the speed at which speed - * and height offsets are trimmed out, but reduces damping and - * increases overshoot. Set this value to zero to completely - * disable all integrator action. - * - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @increment 0.05 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_I_GAIN_THR, 0.3f); - -/** - * Integrator gain pitch - * - * This is the integrator gain on the pitch part of the control loop. - * Increasing this gain increases the speed at which speed - * and height offsets are trimmed out, but reduces damping and - * increases overshoot. Set this value to zero to completely - * disable all integrator action. - * - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @increment 0.05 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f); - -/** - * Maximum vertical acceleration - * - * This is the maximum vertical acceleration (in m/s/s) - * either up or down that the controller will use to correct speed - * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) - * allows for reasonably aggressive pitch changes if required to recover - * from under-speed conditions. - * - * @unit m/s^2 - * @min 1.0 - * @max 10.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); - -/** - * Complementary filter "omega" parameter for speed - * - * This is the cross-over frequency (in radians/second) of the complementary - * filter used to fuse longitudinal acceleration and airspeed to obtain an - * improved airspeed estimate. Increasing this frequency weights the solution - * more towards use of the airspeed sensor, whilst reducing it weights the - * solution more towards use of the accelerometer data. - * - * @unit rad/s - * @min 1.0 - * @max 10.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); - -/** - * Roll -> Throttle feedforward - * - * Increasing this gain turn increases the amount of throttle that will - * be used to compensate for the additional drag created by turning. - * Ideally this should be set to approximately 10 x the extra sink rate - * in m/s created by a 45 degree bank turn. Increase this gain if - * the aircraft initially loses energy in turns and reduce if the - * aircraft initially gains energy in turns. Efficient high aspect-ratio - * aircraft (eg powered sailplanes) can use a lower value, whereas - * inefficient low aspect-ratio models (eg delta wings) can use a higher value. - * - * @min 0.0 - * @max 20.0 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); - -/** - * Speed <--> Altitude priority - * - * This parameter adjusts the amount of weighting that the pitch control - * applies to speed vs height errors. Setting it to 0.0 will cause the - * pitch control to control height and ignore speed errors. This will - * normally improve height accuracy but give larger airspeed errors. - * Setting it to 2.0 will cause the pitch control loop to control speed - * and ignore height errors. This will normally reduce airspeed errors, - * but give larger height errors. The default value of 1.0 allows the pitch - * control to simultaneously control height and speed. - * Note to Glider Pilots - set this parameter to 2.0 (The glider will - * adjust its pitch angle to maintain airspeed, ignoring changes in height). - * - * @min 0.0 - * @max 2.0 - * @decimal 1 - * @increment 1.0 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); - -/** - * Pitch damping factor - * - * This is the damping gain for the pitch demand loop. Increase to add - * damping to correct for oscillations in height. The default value of 0.0 - * will work well provided the pitch to servo controller has been tuned - * properly. - * - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @increment 0.1 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f); - -/** - * Altitude error time constant. - * - * @min 2.0 - * @decimal 2 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f); - -/** - * Height rate feed forward - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.05 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.3f); - -/** - * True airspeed error time constant. - * - * @min 2.0 - * @decimal 2 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f); - -/** - * Minimum groundspeed - * - * The controller will increase the commanded airspeed to maintain - * this minimum groundspeed to the next waypoint. - * - * @unit m/s - * @min 0.0 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f); - -/** - * RC stick configuraton fixed-wing. - * - * Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight. - * - * @min 0 - * @max 3 - * @bit 0 Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick) - * @bit 1 Enable airspeed setpoint via sticks in altitude and position flight mode - * @group FW L1 Control - */ -PARAM_DEFINE_INT32(FW_POS_STK_CONF, 2); - -/** - * Specific total energy rate first order filter time constant. - * - * This filter is applied to the specific total energy rate used for throttle damping. - * - * @min 0.0 - * @max 2 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_STE_R_TC, 0.4f); - - -/** - * True airspeed rate first order filter time constant. - * - * This filter is applied to the true airspeed rate. - * - * @min 0.0 - * @max 2 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_TAS_R_TC, 0.2f); - - -/** - * Specific total energy balance rate feedforward gain. - * - * - * @min 0.5 - * @max 3 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SEB_R_FF, 1.0f); - -/** - * Default target climbrate. - * - * - * The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints. - * In manual modes this defines the maximum rate at which the altitude setpoint can be increased. - * - * - * @unit m/s - * @min 0.5 - * @max 15 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_CLMB_R_SP, 3.0f); - -/** - * Default target sinkrate. - * - * - * The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints. - * In manual modes this defines the maximum rate at which the altitude setpoint can be decreased. - * - * @unit m/s - * @min 0.5 - * @max 15 - * @decimal 2 - * @increment 0.01 - * @group FW TECS - */ -PARAM_DEFINE_FLOAT(FW_T_SINK_R_SP, 2.0f); - -/** - * GPS failure loiter time - * - * The time in seconds the system should do open loop loiter and wait for GPS recovery - * before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. - * Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. - * - * @unit s - * @min 0 - * @max 3600 - * @group Mission - */ -PARAM_DEFINE_INT32(FW_GPSF_LT, 30); - -/** - * GPS failure fixed roll angle - * - * Roll in degrees during the loiter after the vehicle has lost GPS in an auto mode (e.g. mission or loiter). - * Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. - * - * @unit deg - * @min 0.0 - * @max 30.0 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(FW_GPSF_R, 15.0f); - -/** - * Vehicle base weight. - * - * This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value - * disables trim throttle and minimum airspeed compensation based on weight. - * - * @unit kg - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(WEIGHT_BASE, -1.0f); - -/** - * Vehicle gross weight. - * - * This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added - * or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value - * disables trim throttle and minimum airspeed compensation based on weight. - * - * @unit kg - * @decimal 1 - * @increment 0.1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(WEIGHT_GROSS, -1.0f); - -/** - * The aircraft's wing span (length from tip to tip). - * - * This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span) - * - * @unit m - * @min 0.1 - * @decimal 1 - * @increment 0.1 - * @group FW Geometry - */ -PARAM_DEFINE_FLOAT(FW_WING_SPAN, 3.0); - -/** - * Height (AGL) of the wings when the aircraft is on the ground. - * - * This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer - * to give a slight margin here (> 0m) - * - * @unit m - * @min 0.0 - * @decimal 1 - * @increment 1 - * @group FW Geometry - */ -PARAM_DEFINE_FLOAT(FW_WING_HEIGHT, 0.5); - -/** - * Landing flare time - * - * Multiplied by the descent rate to calculate a dynamic altitude at which - * to trigger the flare. - * - * NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude - * - * @unit s - * @min 0.0 - * @max 5.0 - * @decimal 1 - * @increment 0.1 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_FL_TIME, 1.0f); - -/** - * Landing flare sink rate - * - * TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare) - * - * @unit m/s - * @min 0.0 - * @max 1.0 - * @decimal 1 - * @increment 0.1 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_FL_SINK, 0.25f); - -/** - * Maximum lateral position offset for the touchdown point - * - * @unit m - * @min 0.0 - * @max 10.0 - * @decimal 1 - * @increment 1 - * @group FW L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_TD_OFF, 3.0); - -/** - * Landing touchdown nudging option. - * - * Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant - * Approach path nudging: shifts the touchdown point laterally along with the entire approach path - * - * This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the - * desired landing vector. Nuding is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is - * relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle). - * - * @min 0 - * @max 2 - * @value 0 Disable nudging - * @value 1 Nudge approach angle - * @value 2 Nudge approach path - * @group FW L1 Control - */ -PARAM_DEFINE_INT32(FW_LND_NUDGE, 2); - -/** - * Bit mask to set the automatic landing abort conditions. - * - * Terrain estimation: - * bit 0: Abort if terrain is not found - * bit 1: Abort if terrain times out (after a first successful measurement) - * - * The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the - * selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. - * - * TODO: Extend automatic abort conditions - * e.g. glide slope tracking error (horizontal and vertical) - * - * @min 0 - * @max 3 - * @bit 0 Abort if terrain is not found - * @bit 1 Abort if terrain times out (after a first successful measurement) - * @group FW L1 Control - */ -PARAM_DEFINE_INT32(FW_LND_ABORT, 3); diff --git a/src/modules/fw_pos_control_l1/launchdetection/launchdetection_params.c b/src/modules/fw_pos_control_l1/launchdetection/launchdetection_params.c deleted file mode 100644 index 1575cd09b245..000000000000 --- a/src/modules/fw_pos_control_l1/launchdetection/launchdetection_params.c +++ /dev/null @@ -1,110 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file launchdetection_params.c - * - * Parameters for launchdetection - * - * @author Thomas Gubler - */ - -/* - * Catapult launch detection parameters, accessible via MAVLink - * - */ - -/** - * Launch detection - * - * @boolean - * @group FW Launch detection - */ -PARAM_DEFINE_INT32(LAUN_ALL_ON, 0); - -/** - * Catapult accelerometer threshold. - * - * LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. - * - * @unit m/s^2 - * @min 0 - * @decimal 1 - * @increment 0.5 - * @group FW Launch detection - */ -PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f); - -/** - * Catapult time threshold. - * - * LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. - * - * @unit s - * @min 0.0 - * @max 5.0 - * @decimal 2 - * @increment 0.05 - * @group FW Launch detection - */ -PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f); - -/** - * Motor delay - * - * Delay between starting attitude control and powering up the throttle (giving throttle control to the controller) - * Before this timespan is up the throttle will be set to FW_THR_IDLE, set to 0 to deactivate - * - * @unit s - * @min 0.0 - * @max 10.0 - * @decimal 1 - * @increment 0.5 - * @group FW Launch detection - */ -PARAM_DEFINE_FLOAT(LAUN_CAT_MDEL, 0.0f); - -/** - * Maximum pitch before the throttle is powered up (during motor delay phase) - * - * This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on. - * This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep). - * - * @unit deg - * @min 0.0 - * @max 45.0 - * @decimal 1 - * @increment 0.5 - * @group FW Launch detection - */ -PARAM_DEFINE_FLOAT(LAUN_CAT_PMAX, 30.0f); diff --git a/src/modules/fw_pos_control_l1/module.yaml b/src/modules/fw_pos_control_l1/module.yaml new file mode 100644 index 000000000000..b20ac00474c7 --- /dev/null +++ b/src/modules/fw_pos_control_l1/module.yaml @@ -0,0 +1,917 @@ +module_name: fw_pos_control_l1 +parameters: + - definitions: + LAUN_ALL_ON: + default: 0 + description: + short: Launch detection + type: boolean + volatile: false + LAUN_CAT_A: + decimal: 1 + default: 30.0 + description: + long: LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. + short: Catapult accelerometer threshold + increment: 0.5 + min: 0 + type: float + unit: m/s^2 + volatile: false + LAUN_CAT_MDEL: + decimal: 1 + default: 0.0 + description: + long: Delay between starting attitude control and powering up the throttle (giving throttle control to the controller) Before this timespan is up the throttle will be set to FW_THR_IDLE, set to 0 to deactivate + short: Motor delay + increment: 0.5 + max: 10.0 + min: 0.0 + type: float + unit: s + volatile: false + LAUN_CAT_PMAX: + decimal: 1 + default: 30.0 + description: + long: This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on. This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep). + short: Maximum pitch before the throttle is powered up (during motor delay phase) + increment: 0.5 + max: 45.0 + min: 0.0 + type: float + unit: deg + volatile: false + LAUN_CAT_T: + decimal: 2 + default: 0.05 + description: + long: LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. + short: Catapult time threshold + increment: 0.05 + max: 5.0 + min: 0.0 + type: float + unit: s + volatile: false + group: FW Launch detection + - definitions: + FW_WING_HEIGHT: + decimal: 1 + default: 0.5 + description: + long: This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m) + short: Height (AGL) of the wings when the aircraft is on the ground + increment: 1 + min: 0.0 + type: float + unit: m + volatile: false + FW_WING_SPAN: + decimal: 1 + default: 3.0 + description: + long: This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span) + short: The aircraft's wing span (length from tip to tip) + increment: 0.1 + min: 0.1 + type: float + unit: m + volatile: false + group: FW Geometry + - definitions: + FW_CLMBOUT_DIFF: + decimal: 1 + default: 10.0 + description: + long: If the altitude error exceeds this parameter, the system will climb out with maximum throttle and minimum airspeed until it is closer than this distance to the desired altitude. Mostly used for takeoff waypoints / modes. Set to 0 to disable climbout mode (not recommended). + short: Climbout Altitude difference + increment: 0.5 + max: 150.0 + min: 0.0 + type: float + unit: m + volatile: false + FW_L1_DAMPING: + decimal: 2 + default: 0.75 + description: + long: Damping factor for L1 control. + short: L1 damping + increment: 0.05 + max: 0.9 + min: 0.6 + type: float + volatile: false + FW_L1_PERIOD: + decimal: 1 + default: 20.0 + description: + long: Used to determine the L1 gain and controller time constant. This parameter is proportional to the L1 distance (which points ahead of the aircraft on the path it is following). A value of 18-25 seconds works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation. + short: L1 period + increment: 0.5 + max: 50.0 + min: 7.0 + type: float + unit: s + volatile: false + FW_L1_R_SLEW_MAX: + default: 90.0 + description: + long: The maxium change in roll angle setpoint per second. + short: L1 controller roll slew rate limit + increment: 1 + min: 0 + type: float + unit: deg/s + volatile: false + FW_LND_ABORT: + bit: + 0: Abort if terrain is not found + 1: Abort if terrain times out (after a first successful measurement) + default: 3 + description: + long: 'Terrain estimation: bit 0: Abort if terrain is not found bit 1: Abort if terrain times out (after a first successful measurement) The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. TODO: Extend automatic abort conditions e.g. glide slope tracking error (horizontal and vertical)' + short: Bit mask to set the automatic landing abort conditions + max: 3 + min: 0 + type: bitmask + volatile: false + FW_LND_AIRSPD_SC: + decimal: 2 + default: 1.3 + description: + long: Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. FW_AIRSPD_MIN * FW_LND_AIRSPD_SC + short: Min. airspeed scaling factor for landing + increment: 0.01 + max: 1.5 + min: 1.0 + type: float + unit: norm + volatile: false + FW_LND_ANG: + decimal: 1 + default: 5.0 + description: + long: Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. Set this value within the vehicle's performance limits. + short: Maximum landing slope angle + increment: 0.5 + max: 15.0 + min: 1.0 + type: float + unit: deg + volatile: false + FW_LND_EARLYCFG: + default: 0 + description: + long: When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated on the final approach to landing. When enabled, it is already activated when entering the final loiter-down (loiter-to-alt) waypoint before the landing approach. This shifts the (often large) altitude and airspeed errors caused by the configuration change away from the ground such that these are not so critical. It also gives the controller enough time to adapt to the new configuration such that the landing approach starts with a cleaner initial state. + short: Early landing configuration deployment + type: boolean + volatile: false + FW_LND_FLALT: + decimal: 1 + default: 0.5 + description: + long: 'NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude' + short: Landing flare altitude (relative to landing altitude) + increment: 0.5 + min: 0.0 + type: float + unit: m + volatile: false + FW_LND_FL_PMAX: + decimal: 1 + default: 15.0 + description: + long: Maximum pitch during flare, a positive sign means nose up Applied once flaring is triggered + short: Flare, maximum pitch + increment: 0.5 + max: 45.0 + min: 0 + type: float + unit: deg + volatile: false + FW_LND_FL_PMIN: + decimal: 1 + default: 2.5 + description: + long: Minimum pitch during flare, a positive sign means nose up Applied once flaring is triggered + short: Flare, minimum pitch + increment: 0.5 + max: 15.0 + min: 0 + type: float + unit: deg + volatile: false + FW_LND_FL_SINK: + decimal: 1 + default: 0.25 + description: + long: TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare) + short: Landing flare sink rate + increment: 0.1 + max: 1.0 + min: 0.0 + type: float + unit: m/s + volatile: false + FW_LND_FL_TIME: + decimal: 1 + default: 1.0 + description: + long: 'Multiplied by the descent rate to calculate a dynamic altitude at which to trigger the flare. NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude' + short: Landing flare time + increment: 0.1 + max: 5.0 + min: 0.0 + type: float + unit: s + volatile: false + FW_LND_NUDGE: + default: 2 + description: + long: 'Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant Approach path nudging: shifts the touchdown point laterally along with the entire approach path This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the desired landing vector. Nuding is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).' + short: Landing touchdown nudging option + max: 2 + min: 0 + type: enum + values: + 0: Disable nudging + 1: Nudge approach angle + 2: Nudge approach path + volatile: false + FW_LND_TD_OFF: + decimal: 1 + default: 3.0 + description: + short: Maximum lateral position offset for the touchdown point + increment: 1 + max: 10.0 + min: 0.0 + type: float + unit: m + volatile: false + FW_LND_THRTC_SC: + default: 1.0 + description: + long: Set this parameter to less than 1.0 to make TECS react faster to altitude errors during landing than during normal flight (i.e. giving efficiency and low motor wear at high altitudes but control accuracy during landing). During landing, the TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value. + short: Altitude time constant factor for landing + increment: 0.1 + max: 1.0 + min: 0.2 + type: float + volatile: false + FW_LND_USETER: + default: 1 + description: + long: 'NOTE: terrain estimate is currently solely derived from a distance sensor. If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing will be aborted, depending on the criteria set in FW_LND_ABORT. If disabled, FW_LND_ABORT terrain based criteria are ignored.' + short: Use terrain estimation during landing. This is critical for detecting when to flare, and should be enabled if possible + max: 2 + min: 0 + type: enum + values: + 0: Disable the terrain estimate + 1: Use the terrain estimate to trigger the flare (only) + 2: Calculate landing glide slope relative to the terrain estimate + volatile: false + FW_POS_STK_CONF: + bit: + 0: Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick) + 1: Enable airspeed setpoint via sticks in altitude and position flight mode + default: 2 + description: + long: Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight. + short: RC stick configuraton fixed-wing + max: 3 + min: 0 + type: bitmask + volatile: false + FW_P_LIM_MAX: + decimal: 1 + default: 45.0 + description: + long: The maximum pitch angle setpoint for autonomous modes including altitude and position control. + short: Maximum pitch angle + increment: 0.5 + max: 60.0 + min: 0.0 + type: float + unit: deg + volatile: false + FW_P_LIM_MIN: + decimal: 1 + default: -45.0 + description: + long: The minimum pitch angle setpoint for autonomous modes including altitude and position control. + short: Minimum pitch angle + increment: 0.5 + max: 0.0 + min: -60.0 + type: float + unit: deg + volatile: false + FW_R_LIM: + decimal: 1 + default: 50.0 + description: + long: The maximum roll angle setpoint for autonomous modes including altitude and position control. + short: Maximum roll angle + increment: 0.5 + max: 65.0 + min: 35.0 + type: float + unit: deg + volatile: false + FW_THR_IDLE: + decimal: 2 + default: 0.0 + description: + long: This is the minimum throttle while on the ground For aircraft with internal combustion engines, this parameter should be set above the desired idle rpm. For electric motors, idle should typically be set to zero. Note that in automatic modes, "landed" conditions will engage idle throttle. + short: Idle throttle + increment: 0.01 + max: 0.4 + min: 0.0 + type: float + unit: norm + volatile: false + FW_THR_MAX: + decimal: 2 + default: 1.0 + description: + long: This is the maximum throttle % that can be used by the controller. For overpowered aircraft, this should be reduced to a value that provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. + short: Throttle limit max + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FW_THR_MIN: + decimal: 2 + default: 0.0 + description: + long: This is the minimum throttle % that can be used by the controller. For electric aircraft this will normally be set to zero, but can be set to a small non-zero value if a folding prop is fitted to prevent the prop from folding and unfolding repeatedly in-flight or to provide some aerodynamic drag from a turning prop to improve the descent rate. For aircraft with internal combustion engine this parameter should be set for desired idle rpm. + short: Throttle limit min + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FW_THR_SLEW_MAX: + default: 0.0 + description: + long: Maximum slew rate for the commanded throttle + short: Throttle max slew rate + max: 1.0 + min: 0.0 + type: float + volatile: false + FW_THR_TRIM: + decimal: 2 + default: 0.6 + description: + long: This is the throttle setting required to achieve FW_AIRSPD_TRIM during level flight. Most airframes have a value of 0.5-0.7. + short: Trim throttle + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + FW_TKO_PITCH_MIN: + decimal: 1 + default: 10.0 + description: + short: Minimum pitch during takeoff + increment: 0.5 + max: 30.0 + min: -5.0 + type: float + unit: deg + volatile: false + group: FW L1 Control + - definitions: + FW_USE_NPFG: + default: 0 + description: + long: Replaces L1. + short: Use NPFG as lateral-directional guidance law for fixed-wing vehicles + type: boolean + volatile: false + NPFG_DAMPING: + decimal: 2 + default: 0.7 + description: + long: Damping ratio of the NPFG control law. + short: NPFG damping ratio + increment: 0.01 + max: 1.0 + min: 0.1 + type: float + volatile: false + NPFG_EN_MIN_GSP: + default: 1 + description: + short: Enable minimum forward ground speed maintaining excess wind handling logic + type: boolean + volatile: false + NPFG_GSP_MAX_TK: + decimal: 1 + default: 5.0 + description: + long: The maximum value of the minimum forward ground speed that may be commanded by the track keeping excess wind handling logic. Commanded in full at the normalized track error fraction of the track error boundary and reduced to zero on track. + short: Maximum, minimum forward ground speed for track keeping in excess wind + increment: 0.5 + max: 10.0 + min: 0.0 + type: float + unit: m/s + volatile: false + NPFG_LB_PERIOD: + default: 1 + description: + long: Avoids limit cycling from a too aggressively tuned period/damping combination. If set to false, also disables the upper bound NPFG_PERIOD_UB. + short: Enable automatic lower bound on the NPFG period + type: boolean + volatile: false + NPFG_PERIOD: + decimal: 1 + default: 10.0 + description: + long: Period of the NPFG control law. + short: NPFG period + increment: 0.1 + max: 100.0 + min: 1.0 + type: float + unit: s + volatile: false + NPFG_PERIOD_SF: + decimal: 1 + default: 1.5 + description: + long: Multiplied by period for conservative minimum period bounding (when period lower bounding is enabled). 1.0 bounds at marginal stability. + short: Period safety factor + increment: 0.1 + max: 10.0 + min: 1.0 + type: float + volatile: false + NPFG_ROLL_TC: + decimal: 2 + default: 0.5 + description: + long: Time constant of roll controller command / response, modeled as first order delay. Used to determine lower period bound. Setting zero disables automatic period bounding. + short: Roll time constant + increment: 0.05 + max: 2.0 + min: 0.0 + type: float + unit: s + volatile: false + NPFG_SW_DST_MLT: + decimal: 2 + default: 0.32 + description: + long: Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1. 1/pi (0.32) sets the switch distance equivalent to that of the L1 controller. + short: NPFG switch distance multiplier + increment: 0.01 + max: 1.0 + min: 0.1 + type: float + volatile: false + NPFG_TRACK_KEEP: + default: 1 + description: + short: Enable track keeping excess wind handling logic + type: boolean + volatile: false + NPFG_UB_PERIOD: + default: 1 + description: + long: Adapts period to maintain track keeping in variable winds and path curvature. + short: Enable automatic upper bound on the NPFG period + type: boolean + volatile: false + NPFG_WIND_REG: + default: 1 + description: + long: Disabling this parameter further disables all other airspeed incrementation options. + short: Enable wind excess regulation + type: boolean + volatile: false + group: FW NPFG Control + - definitions: + FW_AIRSPD_MAX: + decimal: 1 + default: 20.0 + description: + long: If the CAS (calibrated airspeed) is above this value, the TECS controller will try to decrease airspeed more aggressively. + short: Maximum Airspeed (CAS) + increment: 0.5 + max: 40 + min: 0.5 + type: float + unit: m/s + volatile: false + FW_AIRSPD_MIN: + decimal: 1 + default: 10.0 + description: + long: The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. + short: Minimum Airspeed (CAS) + increment: 0.5 + max: 40 + min: 0.5 + type: float + unit: m/s + volatile: false + FW_AIRSPD_STALL: + decimal: 1 + default: 7.0 + description: + long: The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits. + short: Stall Airspeed (CAS) + increment: 0.5 + max: 40 + min: 0.5 + type: float + unit: m/s + volatile: false + FW_AIRSPD_TRIM: + decimal: 1 + default: 15.0 + description: + long: The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve if no other airspeed setpoint sources are present (e.g. through non-centered RC sticks). + short: Cruise Airspeed (CAS) + increment: 0.5 + max: 40 + min: 0.5 + type: float + unit: m/s + volatile: false + FW_GND_SPD_MIN: + decimal: 1 + default: 5.0 + description: + long: The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. + short: Minimum groundspeed + increment: 0.5 + max: 40 + min: 0.0 + type: float + unit: m/s + volatile: false + FW_T_ALT_TC: + decimal: 2 + default: 5.0 + description: + short: Altitude error time constant + increment: 0.5 + min: 2.0 + type: float + volatile: false + FW_T_CLMB_MAX: + decimal: 1 + default: 5.0 + description: + long: This is the best climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the default value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. The setting of this parameter can be checked by commanding a positive altitude change of 100m in loiter, RTL or guided mode. If the throttle required to climb is close to THR_MAX and the aircraft is maintaining airspeed, then this parameter is set correctly. If the airspeed starts to reduce, then the parameter is set to high, and if the throttle demand required to climb and maintain speed is noticeably less than FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or FW_THR_MAX reduced. + short: Maximum climb rate + increment: 0.5 + max: 15.0 + min: 1.0 + type: float + unit: m/s + volatile: false + FW_T_CLMB_R_SP: + decimal: 2 + default: 3.0 + description: + long: The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be increased. + short: Default target climbrate + increment: 0.01 + max: 15 + min: 0.5 + type: float + unit: m/s + volatile: false + FW_T_HRATE_FF: + decimal: 2 + default: 0.3 + description: + short: Height rate feed forward + increment: 0.05 + max: 1.0 + min: 0.0 + type: float + volatile: false + FW_T_I_GAIN_PIT: + decimal: 2 + default: 0.1 + description: + long: This is the integrator gain on the pitch part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. + short: Integrator gain pitch + increment: 0.05 + max: 2.0 + min: 0.0 + type: float + volatile: false + FW_T_I_GAIN_THR: + decimal: 2 + default: 0.3 + description: + long: This is the integrator gain on the throttle part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. + short: Integrator gain throttle + increment: 0.05 + max: 2.0 + min: 0.0 + type: float + volatile: false + FW_T_PTCH_DAMP: + decimal: 2 + default: 0.1 + description: + long: This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in height. The default value of 0.0 will work well provided the pitch to servo controller has been tuned properly. + short: Pitch damping factor + increment: 0.1 + max: 2.0 + min: 0.0 + type: float + volatile: false + FW_T_RLL2THR: + decimal: 1 + default: 15.0 + description: + long: Increasing this gain turn increases the amount of throttle that will be used to compensate for the additional drag created by turning. Ideally this should be set to approximately 10 x the extra sink rate in m/s created by a 45 degree bank turn. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. Efficient high aspect-ratio aircraft (eg powered sailplanes) can use a lower value, whereas inefficient low aspect-ratio models (eg delta wings) can use a higher value. + short: Roll -> Throttle feedforward + increment: 0.5 + max: 20.0 + min: 0.0 + type: float + volatile: false + FW_T_SEB_R_FF: + decimal: 2 + default: 1.0 + description: + short: Specific total energy balance rate feedforward gain + increment: 0.01 + max: 3 + min: 0.5 + type: float + volatile: false + FW_T_SINK_MAX: + decimal: 1 + default: 5.0 + description: + long: This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft can over-speed on descent. This should be set to a value that can be achieved without exceeding the lower pitch angle limit and without over-speeding the aircraft. + short: Maximum descent rate + increment: 0.5 + max: 15.0 + min: 1.0 + type: float + unit: m/s + volatile: false + FW_T_SINK_MIN: + decimal: 1 + default: 2.0 + description: + long: This is the sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX. + short: Minimum descent rate + increment: 0.5 + max: 5.0 + min: 1.0 + type: float + unit: m/s + volatile: false + FW_T_SINK_R_SP: + decimal: 2 + default: 2.0 + description: + long: The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be decreased. + short: Default target sinkrate + increment: 0.01 + max: 15 + min: 0.5 + type: float + unit: m/s + volatile: false + FW_T_SPDWEIGHT: + decimal: 1 + default: 1.0 + description: + long: This parameter adjusts the amount of weighting that the pitch control applies to speed vs height errors. Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airspeed errors, but give larger height errors. The default value of 1.0 allows the pitch control to simultaneously control height and speed. Note to Glider Pilots - set this parameter to 2.0 (The glider will adjust its pitch angle to maintain airspeed, ignoring changes in height). + short: Speed <--> Altitude priority + increment: 1.0 + max: 2.0 + min: 0.0 + type: float + volatile: false + FW_T_SPD_OMEGA: + decimal: 1 + default: 2.0 + description: + long: This is the cross-over frequency (in radians/second) of the complementary filter used to fuse longitudinal acceleration and airspeed to obtain an improved airspeed estimate. Increasing this frequency weights the solution more towards use of the airspeed sensor, whilst reducing it weights the solution more towards use of the accelerometer data. + short: Complementary filter "omega" parameter for speed + increment: 0.5 + max: 10.0 + min: 1.0 + type: float + unit: rad/s + volatile: false + FW_T_STE_R_TC: + decimal: 2 + default: 0.4 + description: + long: This filter is applied to the specific total energy rate used for throttle damping. + short: Specific total energy rate first order filter time constant + increment: 0.01 + max: 2 + min: 0.0 + type: float + volatile: false + FW_T_TAS_R_TC: + decimal: 2 + default: 0.2 + description: + long: This filter is applied to the true airspeed rate. + short: True airspeed rate first order filter time constant + increment: 0.01 + max: 2 + min: 0.0 + type: float + volatile: false + FW_T_TAS_TC: + decimal: 2 + default: 5.0 + description: + short: True airspeed error time constant + increment: 0.5 + min: 2.0 + type: float + volatile: false + FW_T_THR_DAMP: + decimal: 2 + default: 0.1 + description: + long: This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height. + short: Throttle damping factor + increment: 0.1 + max: 2.0 + min: 0.0 + type: float + volatile: false + FW_T_VERT_ACC: + decimal: 1 + default: 7.0 + description: + long: This is the maximum vertical acceleration (in m/s/s) either up or down that the controller will use to correct speed or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) allows for reasonably aggressive pitch changes if required to recover from under-speed conditions. + short: Maximum vertical acceleration + increment: 0.5 + max: 10.0 + min: 1.0 + type: float + unit: m/s^2 + volatile: false + group: FW TECS + - definitions: + FW_GPSF_LT: + default: 30 + description: + long: The time in seconds the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. + short: GPS failure loiter time + max: 3600 + min: 0 + type: int32 + unit: s + volatile: false + FW_GPSF_R: + decimal: 1 + default: 15.0 + description: + long: Roll in degrees during the loiter after the vehicle has lost GPS in an auto mode (e.g. mission or loiter). Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. + short: GPS failure fixed roll angle + increment: 0.5 + max: 30.0 + min: 0.0 + type: float + unit: deg + volatile: false + WEIGHT_BASE: + decimal: 1 + default: -1.0 + description: + long: This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight. + short: Vehicle base weight + increment: 0.5 + type: float + unit: kg + volatile: false + WEIGHT_GROSS: + decimal: 1 + default: -1.0 + description: + long: This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight. + short: Vehicle gross weight + increment: 0.1 + type: float + unit: kg + volatile: false + group: Mission + - definitions: + RWTO_AIRSPD_SCL: + decimal: 2 + default: 1.3 + description: + long: 'Pitch up will be commanded when the following airspeed is reached: FW_AIRSPD_MIN * RWTO_AIRSPD_SCL' + short: Min airspeed scaling factor for takeoff + increment: 0.01 + max: 2.0 + min: 0.0 + type: float + unit: norm + volatile: false + RWTO_HDG: + default: 0 + description: + long: '0: airframe heading when takeoff is initiated 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF position defined by operator)' + short: Specifies which heading should be held during the runway takeoff ground roll + max: 1 + min: 0 + type: enum + values: + 0: Airframe + 1: Runway + volatile: false + RWTO_L1_PERIOD: + decimal: 1 + default: 5.0 + description: + short: L1 period while steering on runway + increment: 0.1 + max: 100.0 + min: 1.0 + type: float + unit: s + volatile: false + RWTO_MAX_PITCH: + decimal: 1 + default: 20.0 + description: + long: Fixed-wing settings are used if set to 0. Note that there is also a minimum pitch of 10 degrees during takeoff, so this must be larger if set. + short: Max pitch during takeoff + increment: 0.5 + max: 60.0 + min: 0.0 + type: float + unit: deg + volatile: false + RWTO_MAX_THR: + decimal: 2 + default: 1.0 + description: + long: Can be used to test taxi on runway + short: Max throttle during runway takeoff + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + RWTO_NUDGE: + default: 1 + description: + long: This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim. + short: Enable use of yaw stick for nudging the wheel during runway ground roll + type: boolean + volatile: false + RWTO_PSP: + decimal: 1 + default: 0.0 + description: + long: A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached. + short: Pitch setpoint during taxi / before takeoff airspeed is reached + increment: 0.5 + max: 20.0 + min: -10.0 + type: float + unit: deg + volatile: false + RWTO_RAMP_TIME: + decimal: 2 + default: 2.0 + description: + short: Throttle ramp up time for runway takeoff + increment: 0.1 + max: 15.0 + min: 1.0 + type: float + unit: s + volatile: false + RWTO_TKOFF: + default: 0 + description: + short: Runway takeoff with landing gear + type: boolean + volatile: false + group: Runway Takeoff diff --git a/src/modules/fw_pos_control_l1/runway_takeoff/runway_takeoff_params.c b/src/modules/fw_pos_control_l1/runway_takeoff/runway_takeoff_params.c deleted file mode 100644 index cef0b0461ced..000000000000 --- a/src/modules/fw_pos_control_l1/runway_takeoff/runway_takeoff_params.c +++ /dev/null @@ -1,158 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file runway_takeoff_params.c - * - * Parameters for runway takeoff - * - * @author Andreas Antener - */ - -/** - * Runway takeoff with landing gear - * - * @boolean - * @group Runway Takeoff - */ -PARAM_DEFINE_INT32(RWTO_TKOFF, 0); - -/** - * Specifies which heading should be held during the runway takeoff ground roll. - * - * 0: airframe heading when takeoff is initiated - * 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF - * position defined by operator) - * - * @value 0 Airframe - * @value 1 Runway - * @min 0 - * @max 1 - * @group Runway Takeoff - */ -PARAM_DEFINE_INT32(RWTO_HDG, 0); - -/** - * Max throttle during runway takeoff. - * - * Can be used to test taxi on runway - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Runway Takeoff - */ -PARAM_DEFINE_FLOAT(RWTO_MAX_THR, 1.0); - -/** - * Pitch setpoint during taxi / before takeoff airspeed is reached. - * - * A taildragger with steerable wheel might need to pitch up - * a little to keep its wheel on the ground before airspeed - * to takeoff is reached. - * - * @unit deg - * @min -10.0 - * @max 20.0 - * @decimal 1 - * @increment 0.5 - * @group Runway Takeoff - */ -PARAM_DEFINE_FLOAT(RWTO_PSP, 0.0); - -/** - * Max pitch during takeoff. - * - * Fixed-wing settings are used if set to 0. Note that there is also a minimum - * pitch of 10 degrees during takeoff, so this must be larger if set. - * - * @unit deg - * @min 0.0 - * @max 60.0 - * @decimal 1 - * @increment 0.5 - * @group Runway Takeoff - */ -PARAM_DEFINE_FLOAT(RWTO_MAX_PITCH, 20.0); - -/** - * Min airspeed scaling factor for takeoff. - * - * Pitch up will be commanded when the following airspeed is reached: - * FW_AIRSPD_MIN * RWTO_AIRSPD_SCL - * - * @unit norm - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @increment 0.01 - * @group Runway Takeoff - */ -PARAM_DEFINE_FLOAT(RWTO_AIRSPD_SCL, 1.3); - -/** - * Throttle ramp up time for runway takeoff - * - * @unit s - * @min 1.0 - * @max 15.0 - * @decimal 2 - * @increment 0.1 - * @group Runway Takeoff - */ -PARAM_DEFINE_FLOAT(RWTO_RAMP_TIME, 2.0f); - -/** - * L1 period while steering on runway - * - * @unit s - * @min 1.0 - * @max 100.0 - * @decimal 1 - * @increment 0.1 - * @group Runway Takeoff - */ -PARAM_DEFINE_FLOAT(RWTO_L1_PERIOD, 5.0f); - -/** - * Enable use of yaw stick for nudging the wheel during runway ground roll - * - * This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. - * Particularly useful for skinny runways or if the wheel servo is a bit off trim. - * - * @boolean - * @group Runway Takeoff - */ -PARAM_DEFINE_INT32(RWTO_NUDGE, 1); diff --git a/src/modules/gimbal/CMakeLists.txt b/src/modules/gimbal/CMakeLists.txt index a99123b08903..e007c21517f3 100644 --- a/src/modules/gimbal/CMakeLists.txt +++ b/src/modules/gimbal/CMakeLists.txt @@ -43,6 +43,8 @@ px4_add_module( output_mavlink.cpp output_rc.cpp gimbal.cpp + MODULE_CONFIG + module.yaml DEPENDS geo ) diff --git a/src/modules/gimbal/gimbal_params.c b/src/modules/gimbal/gimbal_params.c deleted file mode 100644 index d2013d20e7f1..000000000000 --- a/src/modules/gimbal/gimbal_params.c +++ /dev/null @@ -1,300 +0,0 @@ -/**************************************************************************** -* -* Copyright (c) 2013-2020 PX4 Development Team. All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* 3. Neither the name PX4 nor the names of its contributors may be -* used to endorse or promote products derived from this software -* without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -****************************************************************************/ - - -/** -* Mount input mode -* -* This is the protocol used between the ground station and the autopilot. -* -* Recommended is Auto, RC only or MAVLink gimbal protocol v2. -* The rest will be deprecated. -* -* @value -1 DISABLED -* @value 0 Auto (RC and MAVLink gimbal protocol v2) -* @value 1 RC -* @value 2 MAVLINK_ROI (protocol v1, to be deprecated) -* @value 3 MAVLINK_DO_MOUNT (protocol v1, to be deprecated) -* @value 4 MAVlink gimbal protocol v2 -* @min -1 -* @max 4 -* @group Mount -* @reboot_required true -*/ -PARAM_DEFINE_INT32(MNT_MODE_IN, -1); - -/** -* Mount output mode -* -* This is the protocol used between the autopilot and a connected gimbal. -* -* Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it. -* -* @value 0 AUX -* @value 1 MAVLink gimbal protocol v1 -* @value 2 MAVLink gimbal protocol v2 -* @min 0 -* @max 2 -* @group Mount -* @reboot_required true -*/ -PARAM_DEFINE_INT32(MNT_MODE_OUT, 0); - -/** -* Mavlink System ID of the mount -* -* If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID. -* -* @group Mount -*/ -PARAM_DEFINE_INT32(MNT_MAV_SYSID, 1); - -/** -* Mavlink Component ID of the mount -* -* If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID. -* -* @group Mount -*/ -PARAM_DEFINE_INT32(MNT_MAV_COMPID, 154); - -/** -* Mixer value for selecting normal mode -* -* if required by the gimbal (only in AUX output mode) -* -* @min -1.0 -* @max 1.0 -* @decimal 3 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_OB_NORM_MODE, -1.0f); - -/** -* Mixer value for selecting a locking mode -* -* if required for the gimbal (only in AUX output mode) -* -* @min -1.0 -* @max 1.0 -* @decimal 3 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_OB_LOCK_MODE, 0.0f); - -/** -* Auxiliary channel to control roll (in AUX input or manual mode). -* -* @value 0 Disable -* @value 1 AUX1 -* @value 2 AUX2 -* @value 3 AUX3 -* @value 4 AUX4 -* @value 5 AUX5 -* @value 6 AUX6 -* @min 0 -* @max 6 -* @group Mount -*/ -PARAM_DEFINE_INT32(MNT_MAN_ROLL, 0); - -/** -* Auxiliary channel to control pitch (in AUX input or manual mode). -* -* @value 0 Disable -* @value 1 AUX1 -* @value 2 AUX2 -* @value 3 AUX3 -* @value 4 AUX4 -* @value 5 AUX5 -* @value 6 AUX6 -* @min 0 -* @max 6 -* @group Mount -*/ -PARAM_DEFINE_INT32(MNT_MAN_PITCH, 0); - -/** -* Auxiliary channel to control yaw (in AUX input or manual mode). -* -* @value 0 Disable -* @value 1 AUX1 -* @value 2 AUX2 -* @value 3 AUX3 -* @value 4 AUX4 -* @value 5 AUX5 -* @value 6 AUX6 -* @min 0 -* @max 6 -* @group Mount -*/ -PARAM_DEFINE_INT32(MNT_MAN_YAW, 0); - -/** -* Stabilize the mount -* -* Set to true for servo gimbal, false for passthrough. -* This is required for a gimbal which is not capable of stabilizing itself -* and relies on the IMU's attitude estimation. -* -* @value 0 Disable -* @value 1 Stabilize all axis -* @value 2 Stabilize yaw for absolute/lock mode. -* @min 0 -* @max 2 -* @group Mount -*/ -PARAM_DEFINE_INT32(MNT_DO_STAB, 0); - -/** -* Range of pitch channel output in degrees (only in AUX output mode). -* -* @min 1.0 -* @max 720.0 -* @unit deg -* @decimal 1 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_RANGE_PITCH, 90.0f); - -/** -* Range of roll channel output in degrees (only in AUX output mode). -* -* @min 1.0 -* @max 720.0 -* @unit deg -* @decimal 1 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_RANGE_ROLL, 90.0f); - -/** -* Range of yaw channel output in degrees (only in AUX output mode). -* -* @min 1.0 -* @max 720.0 -* @unit deg -* @decimal 1 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_RANGE_YAW, 360.0f); - -/** -* Offset for pitch channel output in degrees. -* -* @min -360.0 -* @max 360.0 -* @unit deg -* @decimal 1 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_OFF_PITCH, 0.0f); - -/** -* Offset for roll channel output in degrees. -* -* @min -360.0 -* @max 360.0 -* @unit deg -* @decimal 1 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_OFF_ROLL, 0.0f); - -/** -* Offset for yaw channel output in degrees. -* -* @min -360.0 -* @max 360.0 -* @unit deg -* @decimal 1 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_OFF_YAW, 0.0f); - -/** - * Angular pitch rate for manual input in degrees/second. - * - * Full stick input [-1..1] translats to [-pitch rate..pitch rate]. - * - * @min 1.0 - * @max 90.0 - * @unit deg/s - * @group Mount - */ -PARAM_DEFINE_FLOAT(MNT_RATE_PITCH, 30.0f); - -/** - * Angular yaw rate for manual input in degrees/second. - * - * Full stick input [-1..1] translats to [-yaw rate..yaw rate]. - * - * @min 1.0 - * @max 90.0 - * @unit deg/s - * @group Mount - */ -PARAM_DEFINE_FLOAT(MNT_RATE_YAW, 30.0f); - -/** - * Input mode for RC gimbal input - * - * @value 0 Angle - * @value 1 Angular rate - * @min 0 - * @max 1 - * @group Mount - */ -PARAM_DEFINE_INT32(MNT_RC_IN_MODE, 1); - -/** -* Pitch minimum when landed -* -* @min -90.0 -* @max 90.0 -* @unit deg -* @decimal 1 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_LND_P_MIN, -90.0f); - -/** -* Pitch maximum when landed -* -* @min -90.0 -* @max 90.0 -* @unit deg -* @decimal 1 -* @group Mount -*/ -PARAM_DEFINE_FLOAT(MNT_LND_P_MAX, 90.0f); diff --git a/src/modules/gimbal/module.yaml b/src/modules/gimbal/module.yaml new file mode 100644 index 000000000000..1154818bc1dc --- /dev/null +++ b/src/modules/gimbal/module.yaml @@ -0,0 +1,241 @@ +module_name: gimbal +parameters: + - definitions: + MNT_DO_STAB: + default: 0 + description: + long: Set to true for servo gimbal, false for passthrough. This is required for a gimbal which is not capable of stabilizing itself and relies on the IMU's attitude estimation. + short: Stabilize the mount + max: 2 + min: 0 + type: enum + values: + 0: Disable + 1: Stabilize all axis + 2: Stabilize yaw for absolute/lock mode. + volatile: false + MNT_LND_P_MAX: + decimal: 1 + default: 90.0 + description: + short: Pitch maximum when landed + max: 90.0 + min: -90.0 + type: float + unit: deg + volatile: false + MNT_LND_P_MIN: + decimal: 1 + default: -90.0 + description: + short: Pitch minimum when landed + max: 90.0 + min: -90.0 + type: float + unit: deg + volatile: false + MNT_MAN_PITCH: + default: 0 + description: + short: Auxiliary channel to control pitch (in AUX input or manual mode) + max: 6 + min: 0 + type: enum + values: + 0: Disable + 1: AUX1 + 2: AUX2 + 3: AUX3 + 4: AUX4 + 5: AUX5 + 6: AUX6 + volatile: false + MNT_MAN_ROLL: + default: 0 + description: + short: Auxiliary channel to control roll (in AUX input or manual mode) + max: 6 + min: 0 + type: enum + values: + 0: Disable + 1: AUX1 + 2: AUX2 + 3: AUX3 + 4: AUX4 + 5: AUX5 + 6: AUX6 + volatile: false + MNT_MAN_YAW: + default: 0 + description: + short: Auxiliary channel to control yaw (in AUX input or manual mode) + max: 6 + min: 0 + type: enum + values: + 0: Disable + 1: AUX1 + 2: AUX2 + 3: AUX3 + 4: AUX4 + 5: AUX5 + 6: AUX6 + volatile: false + MNT_MAV_COMPID: + default: 154 + description: + long: If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID. + short: Mavlink Component ID of the mount + type: int32 + volatile: false + MNT_MAV_SYSID: + default: 1 + description: + long: If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID. + short: Mavlink System ID of the mount + type: int32 + volatile: false + MNT_MODE_IN: + default: -1 + description: + long: This is the protocol used between the ground station and the autopilot. Recommended is Auto, RC only or MAVLink gimbal protocol v2. The rest will be deprecated. + short: Mount input mode + max: 4 + min: -1 + reboot_required: true + type: enum + values: + -1: DISABLED + 0: Auto (RC and MAVLink gimbal protocol v2) + 1: RC + 2: MAVLINK_ROI (protocol v1, to be deprecated) + 3: MAVLINK_DO_MOUNT (protocol v1, to be deprecated) + 4: MAVlink gimbal protocol v2 + volatile: false + MNT_MODE_OUT: + default: 0 + description: + long: This is the protocol used between the autopilot and a connected gimbal. Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it. + short: Mount output mode + max: 2 + min: 0 + reboot_required: true + type: enum + values: + 0: AUX + 1: MAVLink gimbal protocol v1 + 2: MAVLink gimbal protocol v2 + volatile: false + MNT_OB_LOCK_MODE: + decimal: 3 + default: 0.0 + description: + long: if required for the gimbal (only in AUX output mode) + short: Mixer value for selecting a locking mode + max: 1.0 + min: -1.0 + type: float + volatile: false + MNT_OB_NORM_MODE: + decimal: 3 + default: -1.0 + description: + long: if required by the gimbal (only in AUX output mode) + short: Mixer value for selecting normal mode + max: 1.0 + min: -1.0 + type: float + volatile: false + MNT_OFF_PITCH: + decimal: 1 + default: 0.0 + description: + short: Offset for pitch channel output in degrees + max: 360.0 + min: -360.0 + type: float + unit: deg + volatile: false + MNT_OFF_ROLL: + decimal: 1 + default: 0.0 + description: + short: Offset for roll channel output in degrees + max: 360.0 + min: -360.0 + type: float + unit: deg + volatile: false + MNT_OFF_YAW: + decimal: 1 + default: 0.0 + description: + short: Offset for yaw channel output in degrees + max: 360.0 + min: -360.0 + type: float + unit: deg + volatile: false + MNT_RANGE_PITCH: + decimal: 1 + default: 90.0 + description: + short: Range of pitch channel output in degrees (only in AUX output mode) + max: 720.0 + min: 1.0 + type: float + unit: deg + volatile: false + MNT_RANGE_ROLL: + decimal: 1 + default: 90.0 + description: + short: Range of roll channel output in degrees (only in AUX output mode) + max: 720.0 + min: 1.0 + type: float + unit: deg + volatile: false + MNT_RANGE_YAW: + decimal: 1 + default: 360.0 + description: + short: Range of yaw channel output in degrees (only in AUX output mode) + max: 720.0 + min: 1.0 + type: float + unit: deg + volatile: false + MNT_RATE_PITCH: + default: 30.0 + description: + long: Full stick input [-1..1] translats to [-pitch rate..pitch rate]. + short: Angular pitch rate for manual input in degrees/second + max: 90.0 + min: 1.0 + type: float + unit: deg/s + volatile: false + MNT_RATE_YAW: + default: 30.0 + description: + long: Full stick input [-1..1] translats to [-yaw rate..yaw rate]. + short: Angular yaw rate for manual input in degrees/second + max: 90.0 + min: 1.0 + type: float + unit: deg/s + volatile: false + MNT_RC_IN_MODE: + default: 1 + description: + short: Input mode for RC gimbal input + max: 1 + min: 0 + type: enum + values: + 0: Angle + 1: Angular rate + volatile: false + group: Mount diff --git a/src/modules/gyro_calibration/CMakeLists.txt b/src/modules/gyro_calibration/CMakeLists.txt index cc5381d57b39..07cdbd5cbf55 100644 --- a/src/modules/gyro_calibration/CMakeLists.txt +++ b/src/modules/gyro_calibration/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( SRCS GyroCalibration.cpp GyroCalibration.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue sensor_calibration diff --git a/src/modules/gyro_calibration/module.yaml b/src/modules/gyro_calibration/module.yaml new file mode 100644 index 000000000000..ce315bd83fd4 --- /dev/null +++ b/src/modules/gyro_calibration/module.yaml @@ -0,0 +1,11 @@ +module_name: gyro_calibration +parameters: + - definitions: + IMU_GYRO_CAL_EN: + default: 1 + description: + short: IMU gyro auto calibration enable + reboot_required: true + type: boolean + volatile: false + group: Sensors diff --git a/src/modules/gyro_calibration/parameters.c b/src/modules/gyro_calibration/parameters.c deleted file mode 100644 index dee9df9b744b..000000000000 --- a/src/modules/gyro_calibration/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* IMU gyro auto calibration enable. -* -* @boolean -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_INT32(IMU_GYRO_CAL_EN, 1); diff --git a/src/modules/gyro_fft/CMakeLists.txt b/src/modules/gyro_fft/CMakeLists.txt index 9bf6832ed4be..2391c9db4899 100644 --- a/src/modules/gyro_fft/CMakeLists.txt +++ b/src/modules/gyro_fft/CMakeLists.txt @@ -75,6 +75,8 @@ px4_add_module( ${CMSIS_DSP}/Source/TransformFunctions/arm_cfft_radix4_q15.c ${CMSIS_DSP}/Source/TransformFunctions/arm_rfft_init_q15.c ${CMSIS_DSP}/Source/TransformFunctions/arm_rfft_q15.c + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/modules/gyro_fft/module.yaml b/src/modules/gyro_fft/module.yaml new file mode 100644 index 000000000000..2834f7c100fd --- /dev/null +++ b/src/modules/gyro_fft/module.yaml @@ -0,0 +1,52 @@ +module_name: gyro_fft +parameters: + - definitions: + IMU_GYRO_FFT_EN: + default: 0 + description: + short: IMU gyro FFT enable + reboot_required: true + type: boolean + volatile: false + IMU_GYRO_FFT_LEN: + default: 512 + description: + short: IMU gyro FFT length + reboot_required: true + type: enum + unit: Hz + values: + 256: '256' + 512: '512' + 1024: '1024' + 4096: '4096' + volatile: false + IMU_GYRO_FFT_MAX: + default: 150.0 + description: + short: IMU gyro FFT maximum frequency + max: 1000 + min: 1 + reboot_required: true + type: float + unit: Hz + volatile: false + IMU_GYRO_FFT_MIN: + default: 30.0 + description: + short: IMU gyro FFT minimum frequency + max: 1000 + min: 1 + reboot_required: true + type: float + unit: Hz + volatile: false + IMU_GYRO_FFT_SNR: + default: 10.0 + description: + short: IMU gyro FFT SNR + max: 30 + min: 1 + type: float + volatile: false + group: Sensors diff --git a/src/modules/gyro_fft/parameters.c b/src/modules/gyro_fft/parameters.c deleted file mode 100644 index c0d7e3eebcd9..000000000000 --- a/src/modules/gyro_fft/parameters.c +++ /dev/null @@ -1,85 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* IMU gyro FFT enable. -* -* @boolean -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_INT32(IMU_GYRO_FFT_EN, 0); - -/** -* IMU gyro FFT minimum frequency. -* -* @min 1 -* @max 1000 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_FFT_MIN, 30.f); - -/** -* IMU gyro FFT maximum frequency. -* -* @min 1 -* @max 1000 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_FFT_MAX, 150.f); - -/** -* IMU gyro FFT length. -* -* @value 256 256 -* @value 512 512 -* @value 1024 1024 -* @value 4096 4096 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_INT32(IMU_GYRO_FFT_LEN, 512); - -/** -* IMU gyro FFT SNR. -* -* @min 1 -* @max 30 -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_FFT_SNR, 10.f); diff --git a/src/modules/land_detector/CMakeLists.txt b/src/modules/land_detector/CMakeLists.txt index 632c90d5cf8d..229e07382dbc 100644 --- a/src/modules/land_detector/CMakeLists.txt +++ b/src/modules/land_detector/CMakeLists.txt @@ -42,6 +42,8 @@ px4_add_module( VtolLandDetector.cpp RoverLandDetector.cpp AirshipLandDetector.cpp + MODULE_CONFIG + module.yaml DEPENDS hysteresis ) diff --git a/src/modules/land_detector/land_detector_params.c b/src/modules/land_detector/land_detector_params.c deleted file mode 100644 index 950956a92d91..000000000000 --- a/src/modules/land_detector/land_detector_params.c +++ /dev/null @@ -1,60 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Total flight time in microseconds - * - * Total flight time of this autopilot. Higher 32 bits of the value. - * Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. - * - * @min 0 - * @volatile - * @category system - * @group Land Detector - * - */ -PARAM_DEFINE_INT32(LND_FLIGHT_T_HI, 0); - -/** - * Total flight time in microseconds - * - * Total flight time of this autopilot. Lower 32 bits of the value. - * Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. - * - * @min 0 - * @volatile - * @category system - * @group Land Detector - * - */ -PARAM_DEFINE_INT32(LND_FLIGHT_T_LO, 0); diff --git a/src/modules/land_detector/land_detector_params_fw.c b/src/modules/land_detector/land_detector_params_fw.c deleted file mode 100644 index b2ad0561a054..000000000000 --- a/src/modules/land_detector/land_detector_params_fw.c +++ /dev/null @@ -1,92 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Fixed-wing land detector: Max horizontal velocity threshold - * - * Maximum horizontal velocity allowed in the landed state. - * A factor of 0.7 is applied in case of airspeed-less flying - * (either because no sensor is present or sensor data got invalid in flight). - * - * @unit m/s - * @min 0.5 - * @max 10 - * @decimal 1 - * - * @group Land Detector - */ -PARAM_DEFINE_FLOAT(LNDFW_VEL_XY_MAX, 5.0f); - -/** - * Fixed-wing land detector: Max vertiacal velocity threshold - * - * Maximum vertical velocity allowed in the landed state. - * A factor of 0.7 is applied in case of airspeed-less flying - * (either because no sensor is present or sensor data got invalid in flight). - * - * @unit m/s - * @min 0.1 - * @max 20 - * @decimal 1 - * - * @group Land Detector - */ -PARAM_DEFINE_FLOAT(LNDFW_VEL_Z_MAX, 2.0f); - -/** - * Fixed-wing land detector: Max horizontal acceleration - * - * Maximum horizontal (x,y body axes) acceleration allowed in the landed state - * - * @unit m/s^2 - * @min 2 - * @max 15 - * @decimal 1 - * - * @group Land Detector - */ -PARAM_DEFINE_FLOAT(LNDFW_XYACC_MAX, 8.0f); - -/** - * Fixed-wing land detector: Max airspeed - * - * Maximum airspeed allowed in the landed state - * - * @unit m/s - * @min 2 - * @max 20 - * @decimal 1 - * - * @group Land Detector - */ -PARAM_DEFINE_FLOAT(LNDFW_AIRSPD_MAX, 6.00f); diff --git a/src/modules/land_detector/land_detector_params_mc.c b/src/modules/land_detector/land_detector_params_mc.c deleted file mode 100644 index 3c979ac76708..000000000000 --- a/src/modules/land_detector/land_detector_params_mc.c +++ /dev/null @@ -1,116 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Multicopter land detection trigger time - * - * Total time it takes to go through all three land detection stages: - * ground contact, maybe landed, landed - * when all necessary conditions are constantly met. - * - * @unit s - * @min 0.1 - * @max 10.0 - * @decimal 1 - * - * @group Land Detector - */ -PARAM_DEFINE_FLOAT(LNDMC_TRIG_TIME, 1.0f); - -/** - * Multicopter max climb rate - * - * Maximum vertical velocity allowed in the landed state - * - * @unit m/s - * @decimal 1 - * - * @group Land Detector - */ -PARAM_DEFINE_FLOAT(LNDMC_Z_VEL_MAX, 0.50f); - -/** - * Multicopter max horizontal velocity - * - * Maximum horizontal velocity allowed in the landed state - * - * @unit m/s - * @decimal 1 - * - * @group Land Detector - */ -PARAM_DEFINE_FLOAT(LNDMC_XY_VEL_MAX, 1.5f); - -/** - * Multicopter max rotation - * - * Maximum allowed angular velocity around each axis allowed in the landed state. - * - * @unit deg/s - * @decimal 1 - * - * @group Land Detector - */ -PARAM_DEFINE_FLOAT(LNDMC_ROT_MAX, 20.0f); - -/** - * Maximum altitude for multicopters - * - * The system will obey this limit as a - * hard altitude limit. This setting will - * be consolidated with the GF_MAX_VER_DIST - * parameter. - * A negative value indicates no altitude limitation. - * - * @unit m - * @min -1 - * @max 10000 - * @decimal 2 - * @group Land Detector - * - */ -PARAM_DEFINE_FLOAT(LNDMC_ALT_MAX, -1.0f); - -/** - * Ground effect altitude for multicopters - * - * The height above ground below which ground effect creates barometric altitude errors. - * A negative value indicates no ground effect. - * - * @unit m - * @min -1 - * @decimal 2 - * @group Land Detector - * - */ -PARAM_DEFINE_FLOAT(LNDMC_ALT_GND, 2.f); diff --git a/src/modules/land_detector/module.yaml b/src/modules/land_detector/module.yaml new file mode 100644 index 000000000000..edbbc4fcce88 --- /dev/null +++ b/src/modules/land_detector/module.yaml @@ -0,0 +1,125 @@ +module_name: land_detector +parameters: + - group: Land Detector + definitions: + LND_FLIGHT_T_HI: + category: System + default: 0 + description: + long: Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. + short: Total flight time in microseconds + min: 0 + type: int32 + volatile: true + LND_FLIGHT_T_LO: + category: System + default: 0 + description: + long: Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. + short: Total flight time in microseconds + min: 0 + type: int32 + volatile: true + LNDFW_AIRSPD_MAX: + decimal: 1 + default: 6.0 + description: + long: Maximum airspeed allowed in the landed state + short: 'Fixed-wing land detector: Max airspeed' + max: 20 + min: 2 + type: float + unit: m/s + volatile: false + LNDFW_VEL_XY_MAX: + decimal: 1 + default: 5.0 + description: + long: Maximum horizontal velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight). + short: 'Fixed-wing land detector: Max horizontal velocity threshold' + max: 10 + min: 0.5 + type: float + unit: m/s + volatile: false + LNDFW_VEL_Z_MAX: + decimal: 1 + default: 2.0 + description: + long: Maximum vertical velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight). + short: 'Fixed-wing land detector: Max vertiacal velocity threshold' + max: 20 + min: 0.1 + type: float + unit: m/s + volatile: false + LNDFW_XYACC_MAX: + decimal: 1 + default: 8.0 + description: + long: Maximum horizontal (x,y body axes) acceleration allowed in the landed state + short: 'Fixed-wing land detector: Max horizontal acceleration' + max: 15 + min: 2 + type: float + unit: m/s^2 + volatile: false + LNDMC_ALT_GND: + decimal: 2 + default: 2.0 + description: + long: The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect. + short: Ground effect altitude for multicopters + min: -1 + type: float + unit: m + volatile: false + LNDMC_ALT_MAX: + decimal: 2 + default: -1.0 + description: + long: The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation. + short: Maximum altitude for multicopters + max: 10000 + min: -1 + type: float + unit: m + volatile: false + LNDMC_ROT_MAX: + decimal: 1 + default: 20.0 + description: + long: Maximum allowed angular velocity around each axis allowed in the landed state. + short: Multicopter max rotation + type: float + unit: deg/s + volatile: false + LNDMC_TRIG_TIME: + decimal: 1 + default: 1.0 + description: + long: 'Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met.' + short: Multicopter land detection trigger time + max: 10.0 + min: 0.1 + type: float + unit: s + volatile: false + LNDMC_XY_VEL_MAX: + decimal: 1 + default: 1.5 + description: + long: Maximum horizontal velocity allowed in the landed state + short: Multicopter max horizontal velocity + type: float + unit: m/s + volatile: false + LNDMC_Z_VEL_MAX: + decimal: 1 + default: 0.5 + description: + long: Maximum vertical velocity allowed in the landed state + short: Multicopter max climb rate + type: float + unit: m/s + volatile: false diff --git a/src/modules/landing_target_estimator/CMakeLists.txt b/src/modules/landing_target_estimator/CMakeLists.txt index 146869aa3fe4..434440ab0d1e 100644 --- a/src/modules/landing_target_estimator/CMakeLists.txt +++ b/src/modules/landing_target_estimator/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( landing_target_estimator_main.cpp LandingTargetEstimator.cpp KalmanFilter.cpp + MODULE_CONFIG + module.yaml DEPENDS ) diff --git a/src/modules/landing_target_estimator/landing_target_estimator_params.c b/src/modules/landing_target_estimator/landing_target_estimator_params.c deleted file mode 100644 index 24ee9b772f32..000000000000 --- a/src/modules/landing_target_estimator/landing_target_estimator_params.c +++ /dev/null @@ -1,189 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file landing_target_estimator_params.c - * Landing target estimator algorithm parameters. - * - * @author Nicolas de Palezieux (Sunflower Labs) - * @author Mohammed Kabir - * - */ - -/** - * Landing target mode - * - * Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. - * - * Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. - * Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation. - * - * @min 0 - * @max 1 - * @group Landing target Estimator - * @value 0 Moving - * @value 1 Stationary - */ -PARAM_DEFINE_INT32(LTEST_MODE, 0); - -/** - * Acceleration uncertainty - * - * Variance of acceleration measurement used for landing target position prediction. - * Higher values results in tighter following of the measurements and more lenient outlier rejection - * - * @unit (m/s^2)^2 - * @min 0.01 - * @decimal 2 - * - * @group Landing target Estimator - */ -PARAM_DEFINE_FLOAT(LTEST_ACC_UNC, 10.0f); - -/** - * Landing target measurement uncertainty - * - * Variance of the landing target measurement from the driver. - * Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements. - * - * @unit tan(rad)^2 - * @decimal 4 - * - * @group Landing target Estimator - */ -PARAM_DEFINE_FLOAT(LTEST_MEAS_UNC, 0.005f); - -/** - * Initial landing target position uncertainty - * - * Initial variance of the relative landing target position in x and y direction - * - * @unit m^2 - * @min 0.001 - * @decimal 3 - * - * @group Landing target Estimator - */ -PARAM_DEFINE_FLOAT(LTEST_POS_UNC_IN, 0.1f); - -/** - * Initial landing target velocity uncertainty - * - * Initial variance of the relative landing target velocity in x and y directions - * - * @unit (m/s)^2 - * @min 0.001 - * @decimal 3 - * - * @group Landing target Estimator - */ -PARAM_DEFINE_FLOAT(LTEST_VEL_UNC_IN, 0.1f); - -/** - * Scale factor for sensor measurements in sensor x axis - * - * Landing target x measurements are scaled by this factor before being used - * - * @min 0.01 - * @decimal 3 - * - * @group Landing target Estimator - */ -PARAM_DEFINE_FLOAT(LTEST_SCALE_X, 1.0f); - -/** - * Scale factor for sensor measurements in sensor y axis - * - * Landing target y measurements are scaled by this factor before being used - * - * @min 0.01 - * @decimal 3 - * - * @group Landing target Estimator - */ -PARAM_DEFINE_FLOAT(LTEST_SCALE_Y, 1.0f); - - -/** - * Rotation of IRLOCK sensor relative to airframe - * - * Default orientation of Yaw 90° - * - * @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° - * - * @min -1 - * @max 40 - * @reboot_required true - * @group Landing Target Estimator - */ -PARAM_DEFINE_INT32(LTEST_SENS_ROT, 2); - -/** - * X Position of IRLOCK in body frame (forward) - * - * @reboot_required true - * @unit m - * @decimal 3 - * @group Landing Target Estimator - * - */ -PARAM_DEFINE_FLOAT(LTEST_SENS_POS_X, 0.0f); - -/** - * Y Position of IRLOCK in body frame (right) - * - * @reboot_required true - * @unit m - * @decimal 3 - * @group Landing Target Estimator - * - */ -PARAM_DEFINE_FLOAT(LTEST_SENS_POS_Y, 0.0f); - -/** - * Z Position of IRLOCK in body frame (downward) - * - * @reboot_required true - * @unit m - * @decimal 3 - * @group Landing Target Estimator - * - */ -PARAM_DEFINE_FLOAT(LTEST_SENS_POS_Z, 0.0f); diff --git a/src/modules/landing_target_estimator/module.yaml b/src/modules/landing_target_estimator/module.yaml new file mode 100644 index 000000000000..cda98cfd4075 --- /dev/null +++ b/src/modules/landing_target_estimator/module.yaml @@ -0,0 +1,121 @@ +module_name: landing_target_estimator +parameters: + - definitions: + LTEST_SENS_POS_X: + decimal: 3 + default: 0.0 + description: + short: X Position of IRLOCK in body frame (forward) + reboot_required: true + type: float + unit: m + volatile: false + LTEST_SENS_POS_Y: + decimal: 3 + default: 0.0 + description: + short: Y Position of IRLOCK in body frame (right) + reboot_required: true + type: float + unit: m + volatile: false + LTEST_SENS_POS_Z: + decimal: 3 + default: 0.0 + description: + short: Z Position of IRLOCK in body frame (downward) + reboot_required: true + type: float + unit: m + volatile: false + LTEST_SENS_ROT: + default: 2 + description: + long: "Default orientation of Yaw 90°" + short: Rotation of IRLOCK sensor relative to airframe + max: 40 + min: -1 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + group: Landing Target Estimator + - definitions: + LTEST_ACC_UNC: + decimal: 2 + default: 10.0 + description: + long: Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection + short: Acceleration uncertainty + min: 0.01 + type: float + unit: (m/s^2)^2 + volatile: false + LTEST_MEAS_UNC: + decimal: 4 + default: 0.005 + description: + long: Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements. + short: Landing target measurement uncertainty + type: float + unit: tan(rad)^2 + volatile: false + LTEST_MODE: + default: 0 + description: + long: 'Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.' + short: Landing target mode + max: 1 + min: 0 + type: enum + values: + 0: Moving + 1: Stationary + volatile: false + LTEST_POS_UNC_IN: + decimal: 3 + default: 0.1 + description: + long: Initial variance of the relative landing target position in x and y direction + short: Initial landing target position uncertainty + min: 0.001 + type: float + unit: m^2 + volatile: false + LTEST_SCALE_X: + decimal: 3 + default: 1.0 + description: + long: Landing target x measurements are scaled by this factor before being used + short: Scale factor for sensor measurements in sensor x axis + min: 0.01 + type: float + volatile: false + LTEST_SCALE_Y: + decimal: 3 + default: 1.0 + description: + long: Landing target y measurements are scaled by this factor before being used + short: Scale factor for sensor measurements in sensor y axis + min: 0.01 + type: float + volatile: false + LTEST_VEL_UNC_IN: + decimal: 3 + default: 0.1 + description: + long: Initial variance of the relative landing target velocity in x and y directions + short: Initial landing target velocity uncertainty + min: 0.001 + type: float + unit: (m/s)^2 + volatile: false + group: Landing target Estimator diff --git a/src/modules/load_mon/CMakeLists.txt b/src/modules/load_mon/CMakeLists.txt index a2c6ee06471f..ef127b1cff03 100644 --- a/src/modules/load_mon/CMakeLists.txt +++ b/src/modules/load_mon/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( SRCS LoadMon.cpp LoadMon.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/modules/load_mon/module.yaml b/src/modules/load_mon/module.yaml new file mode 100644 index 000000000000..d53b30ed327b --- /dev/null +++ b/src/modules/load_mon/module.yaml @@ -0,0 +1,10 @@ +module_name: load_mon +parameters: + - definitions: + SYS_STCK_EN: + default: 1 + description: + short: Enable stack checking + type: boolean + volatile: false + group: System diff --git a/src/modules/load_mon/params.c b/src/modules/load_mon/params.c deleted file mode 100644 index c2292d996b7b..000000000000 --- a/src/modules/load_mon/params.c +++ /dev/null @@ -1,40 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Enable stack checking - * - * @boolean - * @group System - */ -PARAM_DEFINE_INT32(SYS_STCK_EN, 1); diff --git a/src/modules/local_position_estimator/CMakeLists.txt b/src/modules/local_position_estimator/CMakeLists.txt index aafaecdef0bd..938cdf508d8b 100644 --- a/src/modules/local_position_estimator/CMakeLists.txt +++ b/src/modules/local_position_estimator/CMakeLists.txt @@ -47,6 +47,8 @@ px4_add_module( sensors/mocap.cpp sensors/land.cpp sensors/landing_target.cpp + MODULE_CONFIG + module.yaml DEPENDS controllib geo diff --git a/src/modules/local_position_estimator/module.yaml b/src/modules/local_position_estimator/module.yaml new file mode 100644 index 000000000000..8ae2d8694ade --- /dev/null +++ b/src/modules/local_position_estimator/module.yaml @@ -0,0 +1,409 @@ +module_name: local_position_estimator +parameters: + - definitions: + LPE_ACC_XY: + decimal: 4 + default: 0.012 + description: + long: Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. + short: Accelerometer xy noise density + max: 2 + min: 1.0e-05 + type: float + unit: m/s^2/sqrt(Hz) + volatile: false + LPE_ACC_Z: + decimal: 4 + default: 0.02 + description: + long: Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) + short: Accelerometer z noise density + max: 2 + min: 1.0e-05 + type: float + unit: m/s^2/sqrt(Hz) + volatile: false + LPE_BAR_Z: + decimal: 2 + default: 3.0 + description: + short: Barometric presssure altitude z standard deviation + max: 100 + min: 0.01 + type: float + unit: m + volatile: false + LPE_EPH_MAX: + decimal: 3 + default: 3.0 + description: + short: Max EPH allowed for GPS initialization + max: 5.0 + min: 1.0 + type: float + unit: m + volatile: false + LPE_EPV_MAX: + decimal: 3 + default: 5.0 + description: + short: Max EPV allowed for GPS initialization + max: 5.0 + min: 1.0 + type: float + unit: m + volatile: false + LPE_FAKE_ORIGIN: + default: 0 + description: + long: (e.g. for AUTO missions using Optical Flow). Initialize the estimator to the LPE_LAT/LON parameters when global information is unavailable + short: Enable publishing of a fake global position + max: 1 + min: 0 + type: int32 + volatile: false + LPE_FGYRO_HP: + decimal: 3 + default: 0.001 + description: + short: Flow gyro high pass filter cut off frequency + max: 2 + min: 0 + type: float + unit: Hz + volatile: false + LPE_FLW_OFF_Z: + decimal: 3 + default: 0.0 + description: + short: Optical flow z offset from center + max: 1 + min: -1 + type: float + unit: m + volatile: false + LPE_FLW_QMIN: + decimal: 0 + default: 150 + description: + short: Optical flow minimum quality threshold + max: 255 + min: 0 + type: int32 + volatile: false + LPE_FLW_R: + decimal: 3 + default: 7.0 + description: + short: Optical flow rotation (roll/pitch) noise gain + max: 10.0 + min: 0.1 + type: float + unit: m/s/rad + volatile: false + LPE_FLW_RR: + decimal: 3 + default: 7.0 + description: + short: Optical flow angular velocity noise gain + max: 10.0 + min: 0.0 + type: float + unit: m/rad + volatile: false + LPE_FLW_SCALE: + decimal: 3 + default: 1.3 + description: + short: Optical flow scale + max: 10.0 + min: 0.1 + type: float + unit: m + volatile: false + LPE_FUSION: + bit: + 0: fuse GPS, requires GPS for alt. init + 1: fuse optical flow + 2: fuse vision position + 3: fuse landing target + 4: fuse land detector + 5: pub agl as lpos down + 6: flow gyro compensation + 7: fuse baro + default: 145 + description: + long: 'Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)' + short: Integer bitmask controlling data fusion + max: 255 + min: 0 + type: bitmask + volatile: false + LPE_GPS_DELAY: + decimal: 2 + default: 0.29 + description: + short: GPS delay compensaton + max: 0.4 + min: 0 + type: float + unit: s + volatile: false + LPE_GPS_VXY: + decimal: 3 + default: 0.25 + description: + long: EPV used if greater than this value. + short: GPS xy velocity standard deviation + max: 2 + min: 0.01 + type: float + unit: m/s + volatile: false + LPE_GPS_VZ: + decimal: 3 + default: 0.25 + description: + short: GPS z velocity standard deviation + max: 2 + min: 0.01 + type: float + unit: m/s + volatile: false + LPE_GPS_XY: + decimal: 2 + default: 1.0 + description: + short: Minimum GPS xy standard deviation, uses reported EPH if greater + max: 5 + min: 0.01 + type: float + unit: m + volatile: false + LPE_GPS_Z: + decimal: 2 + default: 3.0 + description: + short: Minimum GPS z standard deviation, uses reported EPV if greater + max: 200 + min: 0.01 + type: float + unit: m + volatile: false + LPE_LAND_VXY: + decimal: 3 + default: 0.05 + description: + short: Land detector xy velocity standard deviation + max: 10.0 + min: 0.01 + type: float + unit: m/s + volatile: false + LPE_LAND_Z: + decimal: 3 + default: 0.03 + description: + short: Land detector z standard deviation + max: 10.0 + min: 0.001 + type: float + unit: m + volatile: false + LPE_LAT: + decimal: 8 + default: 47.397742 + description: + short: Local origin latitude for nav w/o GPS + max: 90 + min: -90 + type: float + unit: deg + volatile: false + LPE_LDR_OFF_Z: + decimal: 3 + default: 0.0 + description: + short: Lidar z offset from center of vehicle +down + max: 1 + min: -1 + type: float + unit: m + volatile: false + LPE_LDR_Z: + decimal: 3 + default: 0.03 + description: + short: Lidar z standard deviation + max: 1 + min: 0.01 + type: float + unit: m + volatile: false + LPE_LON: + decimal: 8 + default: 8.545594 + description: + short: Local origin longitude for nav w/o GPS + max: 180 + min: -180 + type: float + unit: deg + volatile: false + LPE_LT_COV: + decimal: 2 + default: 0.0001 + description: + short: Minimum landing target standard covariance + long: Uses reported covariance if greater + max: 10 + min: 0.0 + type: float + unit: m^2 + volatile: false + LPE_PN_B: + decimal: 8 + default: 0.001 + description: + short: Accel bias propagation noise density + max: 1 + min: 0 + type: float + unit: m/s^3/sqrt(Hz) + volatile: false + LPE_PN_P: + decimal: 8 + default: 0.1 + description: + long: Increase to trust measurements more. Decrease to trust model more. + short: Position propagation noise density + max: 1 + min: 0 + type: float + unit: m/s/sqrt(Hz) + volatile: false + LPE_PN_T: + decimal: 3 + default: 0.001 + description: + short: Terrain random walk noise density + long: hilly/outdoor (0.1), flat/indoor (0.001) + max: 1 + min: 0 + type: float + unit: m/s/sqrt(Hz) + volatile: false + LPE_PN_V: + decimal: 8 + default: 0.1 + description: + long: Increase to trust measurements more. Decrease to trust model more. + short: Velocity propagation noise density + max: 1 + min: 0 + type: float + unit: m/s^2/sqrt(Hz) + volatile: false + LPE_SNR_OFF_Z: + decimal: 3 + default: 0.0 + description: + short: Sonar z offset from center of vehicle +down + max: 1 + min: -1 + type: float + unit: m + volatile: false + LPE_SNR_Z: + decimal: 3 + default: 0.05 + description: + short: Sonar z standard deviation + max: 1 + min: 0.01 + type: float + unit: m + volatile: false + LPE_T_MAX_GRADE: + decimal: 3 + default: 1.0 + description: + long: Used to calculate increased terrain random walk nosie due to movement. hilly/outdoor (100 = 45 deg), flat/indoor (0 = 0 deg) + short: Terrain maximum percent grade + max: 100 + min: 0 + type: float + unit: '%' + volatile: false + LPE_VIC_P: + decimal: 4 + default: 0.001 + description: + short: Vicon position standard deviation + max: 1 + min: 0.0001 + type: float + unit: m + volatile: false + LPE_VIS_DELAY: + decimal: 2 + default: 0.1 + description: + long: Set to zero to enable automatic compensation from measurement timestamps + short: Vision delay compensation + max: 0.1 + min: 0 + type: float + unit: s + volatile: false + LPE_VIS_XY: + decimal: 3 + default: 0.1 + description: + short: Vision xy standard deviation + max: 1 + min: 0.01 + type: float + unit: m + volatile: false + LPE_VIS_Z: + decimal: 3 + default: 0.5 + description: + short: Vision z standard deviation + max: 100 + min: 0.01 + type: float + unit: m + volatile: false + LPE_VXY_PUB: + decimal: 3 + default: 0.3 + description: + short: Required velocity xy standard deviation to publish position + max: 1.0 + min: 0.01 + type: float + unit: m/s + volatile: false + LPE_X_LP: + decimal: 0 + default: 5.0 + description: + short: Cut frequency for state publication + max: 1000 + min: 5 + type: float + unit: Hz + volatile: false + LPE_Z_PUB: + decimal: 1 + default: 1.0 + description: + short: Required z standard deviation to publish altitude/ terrain + max: 5.0 + min: 0.3 + type: float + unit: m + volatile: false + group: Local Position Estimator diff --git a/src/modules/local_position_estimator/params.c b/src/modules/local_position_estimator/params.c deleted file mode 100644 index daaed04a2550..000000000000 --- a/src/modules/local_position_estimator/params.c +++ /dev/null @@ -1,468 +0,0 @@ -#include - -// 16 is max name length - -/** - * Optical flow z offset from center - * - * @group Local Position Estimator - * @unit m - * @min -1 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_FLW_OFF_Z, 0.0f); - -/** - * Optical flow scale - * - * @group Local Position Estimator - * @unit m - * @min 0.1 - * @max 10.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_FLW_SCALE, 1.3f); - -/** - * Optical flow rotation (roll/pitch) noise gain - * - * @group Local Position Estimator - * @unit m/s/rad - * @min 0.1 - * @max 10.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_FLW_R, 7.0f); - -/** - * Optical flow angular velocity noise gain - * - * @group Local Position Estimator - * @unit m/rad - * @min 0.0 - * @max 10.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_FLW_RR, 7.0f); - -/** - * Optical flow minimum quality threshold - * - * @group Local Position Estimator - * @min 0 - * @max 255 - * @decimal 0 - */ -PARAM_DEFINE_INT32(LPE_FLW_QMIN, 150); - -/** - * Sonar z standard deviation. - * - * @group Local Position Estimator - * @unit m - * @min 0.01 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_SNR_Z, 0.05f); - -/** - * Sonar z offset from center of vehicle +down - * - * @group Local Position Estimator - * @unit m - * @min -1 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_SNR_OFF_Z, 0.00f); - -/** - * Lidar z standard deviation. - * - * @group Local Position Estimator - * @unit m - * @min 0.01 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_LDR_Z, 0.03f); - -/** - * Lidar z offset from center of vehicle +down - * - * @group Local Position Estimator - * @unit m - * @min -1 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_LDR_OFF_Z, 0.00f); - -/** - * Accelerometer xy noise density - * - * Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) - * - * Larger than data sheet to account for tilt error. - * - * @group Local Position Estimator - * @unit m/s^2/sqrt(Hz) - * @min 0.00001 - * @max 2 - * @decimal 4 - */ -PARAM_DEFINE_FLOAT(LPE_ACC_XY, 0.012f); - -/** - * Accelerometer z noise density - * - * Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) - * - * @group Local Position Estimator - * @unit m/s^2/sqrt(Hz) - * @min 0.00001 - * @max 2 - * @decimal 4 - */ -PARAM_DEFINE_FLOAT(LPE_ACC_Z, 0.02f); - -/** - * Barometric presssure altitude z standard deviation. - * - * @group Local Position Estimator - * @unit m - * @min 0.01 - * @max 100 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(LPE_BAR_Z, 3.0f); - -/** - * GPS delay compensaton - * - * @group Local Position Estimator - * @unit s - * @min 0 - * @max 0.4 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(LPE_GPS_DELAY, 0.29f); - - -/** - * Minimum GPS xy standard deviation, uses reported EPH if greater. - * - * @group Local Position Estimator - * @unit m - * @min 0.01 - * @max 5 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(LPE_GPS_XY, 1.0f); - -/** - * Minimum GPS z standard deviation, uses reported EPV if greater. - * - * @group Local Position Estimator - * @unit m - * @min 0.01 - * @max 200 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(LPE_GPS_Z, 3.0f); - -/** - * GPS xy velocity standard deviation. - * - * EPV used if greater than this value. - * - * @group Local Position Estimator - * @unit m/s - * @min 0.01 - * @max 2 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_GPS_VXY, 0.25f); - -/** - * GPS z velocity standard deviation. - * - * @group Local Position Estimator - * @unit m/s - * @min 0.01 - * @max 2 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_GPS_VZ, 0.25f); - -/** - * Max EPH allowed for GPS initialization - * - * @group Local Position Estimator - * @unit m - * @min 1.0 - * @max 5.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_EPH_MAX, 3.0f); - -/** - * Max EPV allowed for GPS initialization - * - * @group Local Position Estimator - * @unit m - * @min 1.0 - * @max 5.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_EPV_MAX, 5.0f); - -/** - * Vision delay compensation. - * - * Set to zero to enable automatic compensation from measurement timestamps - * - * @group Local Position Estimator - * @unit s - * @min 0 - * @max 0.1 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(LPE_VIS_DELAY, 0.1f); - -/** - * Vision xy standard deviation. - * - * @group Local Position Estimator - * @unit m - * @min 0.01 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_VIS_XY, 0.1f); - -/** - * Vision z standard deviation. - * - * @group Local Position Estimator - * @unit m - * @min 0.01 - * @max 100 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_VIS_Z, 0.5f); - -/** - * Vicon position standard deviation. - * - * @group Local Position Estimator - * @unit m - * @min 0.0001 - * @max 1 - * @decimal 4 - */ -PARAM_DEFINE_FLOAT(LPE_VIC_P, 0.001f); - -/** - * Position propagation noise density - * - * Increase to trust measurements more. - * Decrease to trust model more. - * - * @group Local Position Estimator - * @unit m/s/sqrt(Hz) - * @min 0 - * @max 1 - * @decimal 8 - */ -PARAM_DEFINE_FLOAT(LPE_PN_P, 0.1f); - -/** - * Velocity propagation noise density - * - * Increase to trust measurements more. - * Decrease to trust model more. - * - * @group Local Position Estimator - * @unit m/s^2/sqrt(Hz) - * @min 0 - * @max 1 - * @decimal 8 - */ -PARAM_DEFINE_FLOAT(LPE_PN_V, 0.1f); - -/** - * Accel bias propagation noise density - * - * @group Local Position Estimator - * @unit m/s^3/sqrt(Hz) - * @min 0 - * @max 1 - * @decimal 8 - */ -PARAM_DEFINE_FLOAT(LPE_PN_B, 1e-3f); - -/** - * Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001) - * - * @group Local Position Estimator - * @unit m/s/sqrt(Hz) - * @min 0 - * @max 1 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_PN_T, 0.001f); - -/** - * Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) - * - * Used to calculate increased terrain random walk nosie due to movement. - * - * @group Local Position Estimator - * @unit % - * @min 0 - * @max 100 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_T_MAX_GRADE, 1.0f); - -/** - * Flow gyro high pass filter cut off frequency - * - * @group Local Position Estimator - * @unit Hz - * @min 0 - * @max 2 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_FGYRO_HP, 0.001f); - -/** - * Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) - * - * By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable - * - * @group Local Position Estimator - * @min 0 - * @max 1 - */ -PARAM_DEFINE_INT32(LPE_FAKE_ORIGIN, 0); - -/** - * Local origin latitude for nav w/o GPS - * - * @group Local Position Estimator - * @unit deg - * @min -90 - * @max 90 - * @decimal 8 - */ -PARAM_DEFINE_FLOAT(LPE_LAT, 47.397742f); - -/** - * Local origin longitude for nav w/o GPS - * - * @group Local Position Estimator - * @unit deg - * @min -180 - * @max 180 - * @decimal 8 - */ -PARAM_DEFINE_FLOAT(LPE_LON, 8.545594); - -/** - * Cut frequency for state publication - * - * @group Local Position Estimator - * @unit Hz - * @min 5 - * @max 1000 - * @decimal 0 - */ -PARAM_DEFINE_FLOAT(LPE_X_LP, 5.0f); - -/** - * Required velocity xy standard deviation to publish position - * - * @group Local Position Estimator - * @unit m/s - * @min 0.01 - * @max 1.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_VXY_PUB, 0.3f); - -/** - * Required z standard deviation to publish altitude/ terrain - * - * @group Local Position Estimator - * @unit m - * @min 0.3 - * @max 5.0 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(LPE_Z_PUB, 1.0f); - -/** - * Land detector z standard deviation - * - * @group Local Position Estimator - * @unit m - * @min 0.001 - * @max 10.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_LAND_Z, 0.03f); - -/** - * Land detector xy velocity standard deviation - * - * @group Local Position Estimator - * @unit m/s - * @min 0.01 - * @max 10.0 - * @decimal 3 - */ -PARAM_DEFINE_FLOAT(LPE_LAND_VXY, 0.05f); - -/** - * Minimum landing target standard covariance, uses reported covariance if greater. - * - * @group Local Position Estimator - * @unit m^2 - * @min 0.0 - * @max 10 - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(LPE_LT_COV, 0.0001f); - -/** - * Integer bitmask controlling data fusion - * - * Set bits in the following positions to enable: - * 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init - * 1 : Set to true to fuse optical flow data if available - * 2 : Set to true to fuse vision position - * 3 : Set to true to enable landing target - * 4 : Set to true to fuse land detector - * 5 : Set to true to publish AGL as local position down component - * 6 : Set to true to enable flow gyro compensation - * 7 : Set to true to enable baro fusion - * - * default (145 - GPS, baro, land detector) - * - * @group Local Position Estimator - * @min 0 - * @max 255 - * @bit 0 fuse GPS, requires GPS for alt. init - * @bit 1 fuse optical flow - * @bit 2 fuse vision position - * @bit 3 fuse landing target - * @bit 4 fuse land detector - * @bit 5 pub agl as lpos down - * @bit 6 flow gyro compensation - * @bit 7 fuse baro - */ -PARAM_DEFINE_INT32(LPE_FUSION, 145); diff --git a/src/modules/logger/CMakeLists.txt b/src/modules/logger/CMakeLists.txt index 58ecc3f837ef..528827e9757e 100644 --- a/src/modules/logger/CMakeLists.txt +++ b/src/modules/logger/CMakeLists.txt @@ -46,6 +46,8 @@ px4_add_module( log_writer_mavlink.cpp util.cpp watchdog.cpp + MODULE_CONFIG + module.yaml DEPENDS version ) diff --git a/src/modules/logger/module.yaml b/src/modules/logger/module.yaml new file mode 100644 index 000000000000..99c922623101 --- /dev/null +++ b/src/modules/logger/module.yaml @@ -0,0 +1,115 @@ +module_name: logger +parameters: + - definitions: + SDLOG_ALGORITHM: + default: 2 + description: + long: Selects the algorithm used for logfile encryption + short: Logfile Encryption algorithm + type: enum + values: + 0: Disabled + 2: XChaCha20 + 3: AES + volatile: false + SDLOG_BOOT_BAT: + default: 0 + description: + long: When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes. + short: Battery-only Logging + type: boolean + volatile: false + SDLOG_DIRS_MAX: + default: 0 + description: + long: 'If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.' + short: Maximum number of log directories to keep + max: 1000 + min: 0 + reboot_required: true + type: int32 + volatile: false + SDLOG_EXCH_KEY: + default: 1 + description: + long: If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key. + short: Logfile Encryption key exchange key + max: 255 + min: 0 + type: int32 + volatile: false + SDLOG_KEY: + default: 2 + description: + long: Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY + short: Logfile Encryption key index + max: 255 + min: 0 + type: int32 + volatile: false + SDLOG_MISSION: + default: 0 + description: + long: If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). + short: Mission Log + reboot_required: true + type: enum + values: + 0: Disabled + 1: All mission messages + 2: Geotagging messages + volatile: false + SDLOG_MODE: + default: 0 + description: + long: Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. + short: Logging Mode + reboot_required: true + type: enum + values: + -1: disabled + 0: when armed until disarm (default) + 1: from boot until disarm + 2: from boot until shutdown + 3: depending on AUX1 RC channel + volatile: false + SDLOG_PROFILE: + bit: + 0: Default set (general log analysis) + 1: Estimator replay (EKF2) + 2: Thermal calibration + 3: System identification + 4: High rate + 5: Debug + 6: Sensor comparison + 7: Computer Vision and Avoidance + 8: Raw FIFO high-rate IMU (Gyro) + 9: Raw FIFO high-rate IMU (Accel) + 10: Mavlink tunnel message logging + default: 1 + description: + long: 'This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and Magnetomer data) 7 : Topics for computer vision and collision avoidance 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging)' + short: Logging topic profile (integer bitmask) + max: 2047 + min: 0 + reboot_required: true + type: bitmask + volatile: false + SDLOG_UTC_OFFSET: + default: 0 + description: + long: the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets + short: 'UTC offset (unit: min)' + max: 1000 + min: -1000 + type: int32 + unit: min + volatile: false + SDLOG_UUID: + default: 1 + description: + long: If set to 1, add an ID to the log, which uniquely identifies the vehicle + short: Log UUID + type: boolean + volatile: false + group: SD Logging diff --git a/src/modules/logger/params.c b/src/modules/logger/params.c deleted file mode 100644 index 2fe6b07c197f..000000000000 --- a/src/modules/logger/params.c +++ /dev/null @@ -1,221 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * UTC offset (unit: min) - * - * the difference in hours and minutes from Coordinated - * Universal Time (UTC) for a your place and date. - * - * for example, In case of South Korea(UTC+09:00), - * UTC offset is 540 min (9*60) - * - * refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets - * - * @unit min - * @min -1000 - * @max 1000 - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0); - -/** - * Logging Mode - * - * Determines when to start and stop logging. By default, logging is started - * when arming the system, and stopped when disarming. - * - * @value -1 disabled - * @value 0 when armed until disarm (default) - * @value 1 from boot until disarm - * @value 2 from boot until shutdown - * @value 3 depending on AUX1 RC channel - * - * @reboot_required true - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_MODE, 0); - -/** - * Battery-only Logging - * - * When enabled, logging will not start from boot if battery power is not detected - * (e.g. powered via USB on a test bench). This prevents extraneous flight logs from - * being created during bench testing. - * - * Note that this only applies to log-from-boot modes. This has no effect on arm-based - * modes. - * - * @boolean - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_BOOT_BAT, 0); - -/** - * Mission Log - * - * If enabled, a small additional "mission" log file will be written to the SD card. - * The log contains just those messages that are useful for tasks like - * generating flight statistics and geotagging. - * - * The different modes can be used to further reduce the logged data - * (and thus the log file size). For example, choose geotagging mode to - * only log data required for geotagging. - - * Note that the normal/full log is still created, and contains all - * the data in the mission log (and more). - * - * @value 0 Disabled - * @value 1 All mission messages - * @value 2 Geotagging messages - * - * @reboot_required true - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_MISSION, 0); - -/** - * Logging topic profile (integer bitmask). - * - * This integer bitmask controls the set and rates of logged topics. - * The default allows for general log analysis while keeping the - * log file size reasonably small. - * - * Enabling multiple sets leads to higher bandwidth requirements and larger log - * files. - * - * Set bits true to enable: - * 0 : Default set (used for general log analysis) - * 1 : Full rate estimator (EKF2) replay topics - * 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) - * 3 : Topics for system identification (high rate actuator control and IMU data) - * 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) - * 5 : Debugging topics (debug_*.msg topics, for custom code) - * 6 : Topics for sensor comparison (low rate raw IMU, Baro and Magnetomer data) - * 7 : Topics for computer vision and collision avoidance - * 8 : Raw FIFO high-rate IMU (Gyro) - * 9 : Raw FIFO high-rate IMU (Accel) - * 10: Logging of mavlink tunnel message (useful for payload communication debugging) - * - * @min 0 - * @max 2047 - * @bit 0 Default set (general log analysis) - * @bit 1 Estimator replay (EKF2) - * @bit 2 Thermal calibration - * @bit 3 System identification - * @bit 4 High rate - * @bit 5 Debug - * @bit 6 Sensor comparison - * @bit 7 Computer Vision and Avoidance - * @bit 8 Raw FIFO high-rate IMU (Gyro) - * @bit 9 Raw FIFO high-rate IMU (Accel) - * @bit 10 Mavlink tunnel message logging - * @reboot_required true - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_PROFILE, 1); - -/** - * Maximum number of log directories to keep - * - * If there are more log directories than this value, - * the system will delete the oldest directories during startup. - * - * In addition, the system will delete old logs if there is not enough free space left. - * The minimum amount is 300 MB. - * - * If this is set to 0, old directories will only be removed if the free space falls below - * the minimum. - * - * Note: this does not apply to mission log files. - * - * @min 0 - * @max 1000 - * @reboot_required true - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_DIRS_MAX, 0); - -/** - * Log UUID - * - * If set to 1, add an ID to the log, which uniquely identifies the vehicle - * - * @boolean - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_UUID, 1); - -/** - * Logfile Encryption algorithm - * - * Selects the algorithm used for logfile encryption - * - * @value 0 Disabled - * @value 2 XChaCha20 - * @value 3 AES - * - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_ALGORITHM, 2); - -/** - * Logfile Encryption key index - * - * Selects the key in keystore, used for encrypting the log. When using - * a symmetric encryption algorithm, the key is generated at logging start - * and kept stored in this index. For symmetric algorithms, the key is - * volatile and valid only for the duration of logging. The key is stored - * in encrypted format on the sdcard alongside the logfile, using an RSA2048 - * key defined by the SDLOG_EXCHANGE_KEY - * - * @min 0 - * @max 255 - * - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_KEY, 2); - -/** - * Logfile Encryption key exchange key - * - * If the logfile is encrypted using a symmetric key algorithm, - * the used encryption key is generated at logging start and stored - * on the sdcard RSA2048 encrypted using this key. - * - * @min 0 - * @max 255 - * - * @group SD Logging - */ -PARAM_DEFINE_INT32(SDLOG_EXCH_KEY, 1); diff --git a/src/modules/mag_bias_estimator/CMakeLists.txt b/src/modules/mag_bias_estimator/CMakeLists.txt index d52a439d3c88..ad8c8ef4894f 100644 --- a/src/modules/mag_bias_estimator/CMakeLists.txt +++ b/src/modules/mag_bias_estimator/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS MagBiasEstimator.cpp MagBiasEstimator.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/modules/mag_bias_estimator/module.yaml b/src/modules/mag_bias_estimator/module.yaml new file mode 100644 index 000000000000..0c0f1db5fbc7 --- /dev/null +++ b/src/modules/mag_bias_estimator/module.yaml @@ -0,0 +1,23 @@ +module_name: mag_bias_estimator +parameters: + - definitions: + MBE_ENABLE: + default: 1 + description: + long: This enables continuous calibration of the magnetometers before takeoff using gyro data. + short: Enable online mag bias calibration + reboot_required: true + type: boolean + volatile: false + MBE_LEARN_GAIN: + decimal: 1 + default: 18.0 + description: + long: Increase to make the estimator more responsive Decrease to make the estimator more robust to noise + short: Mag bias estimator learning gain + increment: 0.1 + max: 100 + min: 0.1 + type: float + volatile: false + group: Magnetometer Bias Estimator diff --git a/src/modules/mag_bias_estimator/params.c b/src/modules/mag_bias_estimator/params.c deleted file mode 100644 index 8fb3e7bca3be..000000000000 --- a/src/modules/mag_bias_estimator/params.c +++ /dev/null @@ -1,58 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Enable online mag bias calibration - * - * This enables continuous calibration of the magnetometers - * before takeoff using gyro data. - * - * @boolean - * @reboot_required true - * @group Magnetometer Bias Estimator - */ -PARAM_DEFINE_INT32(MBE_ENABLE, 1); - -/** - * Mag bias estimator learning gain - * - * Increase to make the estimator more responsive - * Decrease to make the estimator more robust to noise - * - * @min 0.1 - * @max 100 - * @increment 0.1 - * @decimal 1 - * @group Magnetometer Bias Estimator - */ -PARAM_DEFINE_FLOAT(MBE_LEARN_GAIN, 18.f); diff --git a/src/modules/manual_control/CMakeLists.txt b/src/modules/manual_control/CMakeLists.txt index c96478afdf48..562b2a7d8b7b 100644 --- a/src/modules/manual_control/CMakeLists.txt +++ b/src/modules/manual_control/CMakeLists.txt @@ -41,6 +41,8 @@ px4_add_module( ManualControl.hpp ManualControlSelector.hpp ManualControlSelector.cpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/modules/manual_control/manual_control_params.c b/src/modules/manual_control/manual_control_params.c deleted file mode 100644 index c17dc15ad78b..000000000000 --- a/src/modules/manual_control/manual_control_params.c +++ /dev/null @@ -1,43 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Enable arm/disarm stick gesture - * - * This determines if moving the left stick to the lower right - * arms and to the lower left disarms the vehicle. - * - * @boolean - * @group Manual Control - */ -PARAM_DEFINE_INT32(MAN_ARM_GESTURE, 1); diff --git a/src/modules/manual_control/module.yaml b/src/modules/manual_control/module.yaml new file mode 100644 index 000000000000..94a53a87f9fc --- /dev/null +++ b/src/modules/manual_control/module.yaml @@ -0,0 +1,11 @@ +module_name: manual_control +parameters: + - definitions: + MAN_ARM_GESTURE: + default: 1 + description: + long: This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle. + short: Enable arm/disarm stick gesture + type: boolean + volatile: false + group: Manual Control diff --git a/src/modules/mavlink/mavlink_params.c b/src/modules/mavlink/mavlink_params.c deleted file mode 100644 index 59078c952503..000000000000 --- a/src/modules/mavlink/mavlink_params.c +++ /dev/null @@ -1,168 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * MAVLink system ID - * @group MAVLink - * @min 1 - * @max 250 - * @reboot_required true - */ -PARAM_DEFINE_INT32(MAV_SYS_ID, 1); - -/** - * MAVLink component ID - * @group MAVLink - * @min 1 - * @max 250 - * @reboot_required true - */ -PARAM_DEFINE_INT32(MAV_COMP_ID, 1); - -/** - * MAVLink protocol version - * @group MAVLink - * @value 0 Default to 1, switch to 2 if GCS sends version 2 - * @value 1 Always use version 1 - * @value 2 Always use version 2 - */ -PARAM_DEFINE_INT32(MAV_PROTO_VER, 0); - -/** - * MAVLink SiK Radio ID - * - * When non-zero the MAVLink app will attempt to configure the - * SiK radio to this ID and re-set the parameter to 0. If the value - * is negative it will reset the complete radio config to - * factory defaults. Only applies if this mavlink instance is going through a SiK radio - * - * @group MAVLink - * @min -1 - * @max 240 - */ -PARAM_DEFINE_INT32(MAV_SIK_RADIO_ID, 0); - -/** - * MAVLink airframe type - * - * @min 0 - * @max 22 - * @value 0 Generic micro air vehicle - * @value 1 Fixed wing aircraft - * @value 2 Quadrotor - * @value 3 Coaxial helicopter - * @value 4 Normal helicopter with tail rotor - * @value 7 Airship, controlled - * @value 8 Free balloon, uncontrolled - * @value 10 Ground rover - * @value 11 Surface vessel, boat, ship - * @value 12 Submarine - * @value 13 Hexarotor - * @value 14 Octorotor - * @value 15 Tricopter - * @value 19 VTOL Two-rotor Tailsitter - * @value 20 VTOL Quad-rotor Tailsitter - * @value 21 VTOL Tiltrotor - * @value 22 VTOL Standard (separate fixed rotors for hover and cruise flight) - * @value 23 VTOL Tailsitter - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_TYPE, 0); - -/** - * Use/Accept HIL GPS message even if not in HIL mode - * - * If set to 1 incoming HIL GPS messages are parsed. - * - * @boolean - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_USEHILGPS, 0); - -/** - * Forward external setpoint messages - * - * If set to 1 incoming external setpoint messages will be directly forwarded - * to the controllers if in offboard control mode - * - * @boolean - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1); - -/** - * Parameter hash check. - * - * Disabling the parameter hash check functionality will make the mavlink instance - * stream parameters continuously. - * - * @boolean - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_HASH_CHK_EN, 1); - -/** - * Heartbeat message forwarding. - * - * The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. - * The main reason for disabling heartbeats to be forwarded is because they confuse dronekit. - * - * @boolean - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_HB_FORW_EN, 1); - -/** - * Activate ODOMETRY loopback. - * - * If set, it gets the data from 'vehicle_visual_odometry' instead of 'vehicle_odometry' - * serving as a loopback of the received ODOMETRY messages on the Mavlink receiver. - * - * @boolean - * @group MAVLink - */ -PARAM_DEFINE_INT32(MAV_ODOM_LP, 0); - -/** - * Timeout in seconds for the RADIO_STATUS reports coming in - * - * If the connected radio stops reporting RADIO_STATUS for a certain time, - * a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow - * control is reset. - * - * @group MAVLink - * @unit s - * @min 1 - * @max 250 - */ -PARAM_DEFINE_INT32(MAV_RADIO_TOUT, 5); diff --git a/src/modules/mavlink/module.yaml b/src/modules/mavlink/module.yaml index 10da1b888368..c7e419ced459 100644 --- a/src/modules/mavlink/module.yaml +++ b/src/modules/mavlink/module.yaml @@ -1,178 +1,272 @@ __max_num_config_instances: &max_num_config_instances 3 - module_name: MAVLink serial_config: - - command: | - if [ $SERIAL_DEV != ethernet ]; then - set MAV_ARGS "-d ${SERIAL_DEV} -b p:${BAUD_PARAM} -m p:MAV_${i}_MODE -r p:MAV_${i}_RATE" - else - set MAV_ARGS "-u p:MAV_${i}_UDP_PRT -o p:MAV_${i}_REMOTE_PRT -m p:MAV_${i}_MODE -r p:MAV_${i}_RATE" - if param compare MAV_${i}_BROADCAST 1 - then - set MAV_ARGS "${MAV_ARGS} -p" - fi - if param compare MAV_${i}_BROADCAST 2 - then - set MAV_ARGS "${MAV_ARGS} -c" - fi - fi - if param compare MAV_${i}_FORWARD 1 - then - set MAV_ARGS "${MAV_ARGS} -f" - fi - if param compare MAV_${i}_RADIO_CTL 1 - then - set MAV_ARGS "${MAV_ARGS} -s" - fi - if param compare MAV_${i}_FLOW_CTRL 0 - then - set MAV_ARGS "${MAV_ARGS} -Z" - fi - if param compare MAV_${i}_FLOW_CTRL 1 - then - set MAV_ARGS "${MAV_ARGS} -z" - fi - mavlink start ${MAV_ARGS} -x - port_config_param: - name: MAV_${i}_CONFIG - group: MAVLink - # MAVLink instances: - # 0: Telem1 Port (Telemetry Link) - # 1: Telem2 Port (Companion Link). Disabled by default to reduce RAM usage - # 2: Board-specific / no fixed function or port - default: [TEL1, "", ""] - num_instances: *max_num_config_instances - supports_networking: true - + - command: | + if [ $SERIAL_DEV != ethernet ]; then + set MAV_ARGS "-d ${SERIAL_DEV} -b p:${BAUD_PARAM} -m p:MAV_${i}_MODE -r p:MAV_${i}_RATE" + else + set MAV_ARGS "-u p:MAV_${i}_UDP_PRT -o p:MAV_${i}_REMOTE_PRT -m p:MAV_${i}_MODE -r p:MAV_${i}_RATE" + if param compare MAV_${i}_BROADCAST 1 + then + set MAV_ARGS "${MAV_ARGS} -p" + fi + if param compare MAV_${i}_BROADCAST 2 + then + set MAV_ARGS "${MAV_ARGS} -c" + fi + fi + if param compare MAV_${i}_FORWARD 1 + then + set MAV_ARGS "${MAV_ARGS} -f" + fi + if param compare MAV_${i}_RADIO_CTL 1 + then + set MAV_ARGS "${MAV_ARGS} -s" + fi + if param compare MAV_${i}_FLOW_CTRL 0 + then + set MAV_ARGS "${MAV_ARGS} -Z" + fi + if param compare MAV_${i}_FLOW_CTRL 1 + then + set MAV_ARGS "${MAV_ARGS} -z" + fi + mavlink start ${MAV_ARGS} -x + port_config_param: + name: MAV_${i}_CONFIG + group: MAVLink + # MAVLink instances: + # 0: Telem1 Port (Telemetry Link) + # 1: Telem2 Port (Companion Link). Disabled by default to reduce RAM usage + # 2: Board-specific / no fixed function or port + default: [TEL1, "", ""] + num_instances: *max_num_config_instances + supports_networking: true parameters: - - group: MAVLink - definitions: - MAV_${i}_MODE: - description: - short: MAVLink Mode for instance ${i} - long: | - The MAVLink Mode defines the set of streamed messages (for example the - vehicle's attitude) and their sending rates. - - type: enum - values: - 0: Normal - 1: Custom - 2: Onboard - 3: OSD - 4: Magic - 5: Config - #6: Iridium # as the user does not need to configure this, hide it from the UI - 7: Minimal - 8: External Vision - #9: External Vision Minimal # hidden - 10: Gimbal - 11: Onboard Low Bandwidth - reboot_required: true - num_instances: *max_num_config_instances - default: [0, 2, 0] - - MAV_${i}_RATE: - description: - short: Maximum MAVLink sending rate for instance ${i} - long: | - 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). - - type: int32 - min: 0 - unit: B/s - reboot_required: true - num_instances: *max_num_config_instances - default: [1200, 0, 0] - - MAV_${i}_FORWARD: - description: - short: Enable MAVLink Message forwarding for instance ${i} - long: | - 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). - - type: boolean - reboot_required: true - num_instances: *max_num_config_instances - default: [true, false, false] - - MAV_${i}_RADIO_CTL: - description: - short: Enable software throttling of mavlink on instance ${i} - long: | - 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. - - type: boolean - reboot_required: true - num_instances: *max_num_config_instances - default: [true, true, true] - - MAV_${i}_UDP_PRT: - description: - short: MAVLink Network Port for instance ${i} - long: | - If ethernet enabled and selected as configuration for MAVLink instance ${i}, - selected udp port will be set and used in MAVLink instance ${i}. - - type: int32 - reboot_required: true - num_instances: *max_num_config_instances - default: [14556, 0, 0] - requires_ethernet: true - - MAV_${i}_REMOTE_PRT: - description: - short: MAVLink Remote Port for instance ${i} - long: | - If ethernet enabled and selected as configuration for MAVLink instance ${i}, - selected remote port will be set and used in MAVLink instance ${i}. - - type: int32 - reboot_required: true - num_instances: *max_num_config_instances - default: [14550, 0, 0] - requires_ethernet: true - - MAV_${i}_BROADCAST: - description: - short: Broadcast heartbeats on local network for MAVLink instance ${i} - long: | - This allows a ground control station to automatically find the drone - on the local network. + - group: MAVLink + definitions: + MAV_${i}_MODE: + description: + short: MAVLink Mode for instance ${i} + long: | + The MAVLink Mode defines the set of streamed messages (for example the + vehicle's attitude) and their sending rates. + type: enum + values: + 0: Normal + 1: Custom + 2: Onboard + 3: OSD + 4: Magic + 5: Config + #6: Iridium # as the user does not need to configure this, hide it from the UI + 7: Minimal + 8: External Vision + #9: External Vision Minimal # hidden + 10: Gimbal + 11: Onboard Low Bandwidth + reboot_required: true + num_instances: *max_num_config_instances + default: [0, 2, 0] + MAV_${i}_RATE: + description: + short: Maximum MAVLink sending rate for instance ${i} + long: | + 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. - type: enum - values: - 0: Never broadcast - 1: Always broadcast - 2: Only multicast - num_instances: *max_num_config_instances - default: [1, 0, 0] - requires_ethernet: true + 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). + type: int32 + min: 0 + unit: B/s + reboot_required: true + num_instances: *max_num_config_instances + default: [1200, 0, 0] + MAV_${i}_FORWARD: + description: + short: Enable MAVLink Message forwarding for instance ${i} + long: | + If enabled, forward incoming MAVLink messages to other MAVLink ports if the + message is either broadcast or the target is not the autopilot. - MAV_${i}_FLOW_CTRL: - description: - short: Enable serial flow control for instance ${i} - long: | - This is used to force flow control on or off for the the mavlink - instance. By default it is auto detected. Use when auto detction fails. + 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). + type: boolean + reboot_required: true + num_instances: *max_num_config_instances + default: [true, false, false] + MAV_${i}_RADIO_CTL: + description: + short: Enable software throttling of mavlink on instance ${i} + long: | + If enabled, MAVLink messages will be throttled according to + `txbuf` field reported by radio_status. - type: enum - values: - 0: Force off - 1: Force on - 2: Auto-detected - num_instances: *max_num_config_instances - default: [2, 2, 2] + Requires a radio to send the mavlink message RADIO_STATUS. + type: boolean + reboot_required: true + num_instances: *max_num_config_instances + default: [true, true, true] + MAV_${i}_UDP_PRT: + description: + short: MAVLink Network Port for instance ${i} + long: | + If ethernet enabled and selected as configuration for MAVLink instance ${i}, + selected udp port will be set and used in MAVLink instance ${i}. + type: int32 + reboot_required: true + num_instances: *max_num_config_instances + default: [14556, 0, 0] + requires_ethernet: true + MAV_${i}_REMOTE_PRT: + description: + short: MAVLink Remote Port for instance ${i} + long: | + If ethernet enabled and selected as configuration for MAVLink instance ${i}, + selected remote port will be set and used in MAVLink instance ${i}. + type: int32 + reboot_required: true + num_instances: *max_num_config_instances + default: [14550, 0, 0] + requires_ethernet: true + MAV_${i}_BROADCAST: + description: + short: Broadcast heartbeats on local network for MAVLink instance ${i} + long: | + This allows a ground control station to automatically find the drone + on the local network. + type: enum + values: + 0: Never broadcast + 1: Always broadcast + 2: Only multicast + num_instances: *max_num_config_instances + default: [1, 0, 0] + requires_ethernet: true + MAV_${i}_FLOW_CTRL: + description: + short: Enable serial flow control for instance ${i} + long: | + This is used to force flow control on or off for the the mavlink + instance. By default it is auto detected. Use when auto detction fails. + type: enum + values: + 0: Force off + 1: Force on + 2: Auto-detected + num_instances: *max_num_config_instances + default: [2, 2, 2] + - definitions: + MAV_COMP_ID: + default: 1 + description: + short: MAVLink component ID + max: 250 + min: 1 + reboot_required: true + type: int32 + volatile: false + MAV_FWDEXTSP: + default: 1 + description: + long: If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode + short: Forward external setpoint messages + type: boolean + volatile: false + MAV_HASH_CHK_EN: + default: 1 + description: + long: Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously. + short: Parameter hash check + type: boolean + volatile: false + MAV_HB_FORW_EN: + default: 1 + description: + long: The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit. + short: Heartbeat message forwarding + type: boolean + volatile: false + MAV_ODOM_LP: + default: 0 + description: + long: If set, it gets the data from 'vehicle_visual_odometry' instead of 'vehicle_odometry' serving as a loopback of the received ODOMETRY messages on the Mavlink receiver. + short: Activate ODOMETRY loopback + type: boolean + volatile: false + MAV_PROTO_VER: + default: 0 + description: + short: MAVLink protocol version + type: enum + values: + 0: Default to 1, switch to 2 if GCS sends version 2 + 1: Always use version 1 + 2: Always use version 2 + volatile: false + MAV_RADIO_TOUT: + default: 5 + description: + long: If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset. + short: Timeout in seconds for the RADIO_STATUS reports coming in + max: 250 + min: 1 + type: int32 + unit: s + volatile: false + MAV_SIK_RADIO_ID: + default: 0 + description: + long: When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio + short: MAVLink SiK Radio ID + max: 240 + min: -1 + type: int32 + volatile: false + MAV_SYS_ID: + default: 1 + description: + short: MAVLink system ID + max: 250 + min: 1 + reboot_required: true + type: int32 + volatile: false + MAV_TYPE: + default: 0 + description: + short: MAVLink airframe type + max: 22 + min: 0 + type: enum + values: + 0: Generic micro air vehicle + 1: Fixed wing aircraft + 2: Quadrotor + 3: Coaxial helicopter + 4: Normal helicopter with tail rotor + 7: Airship, controlled + 8: Free balloon, uncontrolled + 10: Ground rover + 11: Surface vessel, boat, ship + 12: Submarine + 13: Hexarotor + 14: Octorotor + 15: Tricopter + 19: VTOL Two-rotor Tailsitter + 20: VTOL Quad-rotor Tailsitter + 21: VTOL Tiltrotor + 22: VTOL Standard (separate fixed rotors for hover and cruise flight) + 23: VTOL Tailsitter + volatile: false + MAV_USEHILGPS: + default: 0 + description: + long: If set to 1 incoming HIL GPS messages are parsed. + short: Use/Accept HIL GPS message even if not in HIL mode + type: boolean + volatile: false + group: MAVLink diff --git a/src/modules/mc_att_control/CMakeLists.txt b/src/modules/mc_att_control/CMakeLists.txt index abd0f4ff9c33..cae3c17ab939 100644 --- a/src/modules/mc_att_control/CMakeLists.txt +++ b/src/modules/mc_att_control/CMakeLists.txt @@ -41,6 +41,8 @@ px4_add_module( SRCS mc_att_control_main.cpp mc_att_control.hpp + MODULE_CONFIG + module.yaml DEPENDS AttitudeControl mathlib diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c deleted file mode 100644 index f45e85694263..000000000000 --- a/src/modules/mc_att_control/mc_att_control_params.c +++ /dev/null @@ -1,160 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mc_att_control_params.c - * Parameters for multicopter attitude controller. - * - * @author Lorenz Meier - * @author Anton Babushkin - */ - -/** - * Roll P gain - * - * Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - * - * @min 0.0 - * @max 12 - * @decimal 2 - * @increment 0.1 - * @group Multicopter Attitude Control - */ -PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.5f); - -/** - * Pitch P gain - * - * Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - * - * @min 0.0 - * @max 12 - * @decimal 2 - * @increment 0.1 - * @group Multicopter Attitude Control - */ -PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.5f); - -/** - * Yaw P gain - * - * Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - * - * @min 0.0 - * @max 5 - * @decimal 2 - * @increment 0.1 - * @group Multicopter Attitude Control - */ -PARAM_DEFINE_FLOAT(MC_YAW_P, 2.8f); - -/** - * Yaw weight - * - * A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. - * Deprioritizing yaw is necessary because multicopters have much less control authority - * in yaw compared to the other axes and it makes sense because yaw is not critical for - * stable hovering or 3D navigation. - * - * For yaw control tuning use MC_YAW_P. This ratio has no inpact on the yaw gain. - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.1 - * @group Multicopter Attitude Control - */ -PARAM_DEFINE_FLOAT(MC_YAW_WEIGHT, 0.4f); - -/** - * Max roll rate - * - * Limit for roll rate in manual and auto modes (except acro). - * Has effect for large rotations in autonomous mode, to avoid large control - * output and mixer saturation. - * - * This is not only limited by the vehicle's properties, but also by the maximum - * measurement rate of the gyro. - * - * @unit deg/s - * @min 0.0 - * @max 1800.0 - * @decimal 1 - * @increment 5 - * @group Multicopter Attitude Control - */ -PARAM_DEFINE_FLOAT(MC_ROLLRATE_MAX, 220.0f); - -/** - * Max pitch rate - * - * Limit for pitch rate in manual and auto modes (except acro). - * Has effect for large rotations in autonomous mode, to avoid large control - * output and mixer saturation. - * - * This is not only limited by the vehicle's properties, but also by the maximum - * measurement rate of the gyro. - * - * @unit deg/s - * @min 0.0 - * @max 1800.0 - * @decimal 1 - * @increment 5 - * @group Multicopter Attitude Control - */ -PARAM_DEFINE_FLOAT(MC_PITCHRATE_MAX, 220.0f); - -/** - * Max yaw rate - * - * @unit deg/s - * @min 0.0 - * @max 1800.0 - * @decimal 1 - * @increment 5 - * @group Multicopter Attitude Control - */ -PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 200.0f); - -/** - * Manual tilt input filter time constant - * - * Setting this parameter to 0 disables the filter - * - * @unit s - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MC_MAN_TILT_TAU, 0.0f); diff --git a/src/modules/mc_att_control/module.yaml b/src/modules/mc_att_control/module.yaml new file mode 100644 index 000000000000..4db52d7a3834 --- /dev/null +++ b/src/modules/mc_att_control/module.yaml @@ -0,0 +1,96 @@ +module_name: mc_att_control +parameters: + - definitions: + MC_PITCHRATE_MAX: + decimal: 1 + default: 220.0 + description: + long: Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro. + short: Max pitch rate + increment: 5 + max: 1800.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + MC_PITCH_P: + decimal: 2 + default: 6.5 + description: + long: Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + short: Pitch P gain + increment: 0.1 + max: 12 + min: 0.0 + type: float + volatile: false + MC_ROLLRATE_MAX: + decimal: 1 + default: 220.0 + description: + long: Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro. + short: Max roll rate + increment: 5 + max: 1800.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + MC_ROLL_P: + decimal: 2 + default: 6.5 + description: + long: Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + short: Roll P gain + increment: 0.1 + max: 12 + min: 0.0 + type: float + volatile: false + MC_YAWRATE_MAX: + decimal: 1 + default: 200.0 + description: + short: Max yaw rate + increment: 5 + max: 1800.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + MC_YAW_P: + decimal: 2 + default: 2.8 + description: + long: Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + short: Yaw P gain + increment: 0.1 + max: 5 + min: 0.0 + type: float + volatile: false + MC_YAW_WEIGHT: + decimal: 2 + default: 0.4 + description: + long: A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no inpact on the yaw gain. + short: Yaw weight + increment: 0.1 + max: 1.0 + min: 0.0 + type: float + volatile: false + group: Multicopter Attitude Control + - definitions: + MC_MAN_TILT_TAU: + decimal: 2 + default: 0.0 + description: + long: Setting this parameter to 0 disables the filter + short: Manual tilt input filter time constant + max: 2.0 + min: 0.0 + type: float + unit: s + volatile: false + group: Multicopter Position Control diff --git a/src/modules/mc_autotune_attitude_control/CMakeLists.txt b/src/modules/mc_autotune_attitude_control/CMakeLists.txt index 62dfc9ca3c4e..b318158d2494 100644 --- a/src/modules/mc_autotune_attitude_control/CMakeLists.txt +++ b/src/modules/mc_autotune_attitude_control/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( SRCS mc_autotune_attitude_control.cpp mc_autotune_attitude_control.hpp + MODULE_CONFIG + module.yaml DEPENDS hysteresis mathlib diff --git a/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c b/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c deleted file mode 100644 index e530eb75a8f0..000000000000 --- a/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c +++ /dev/null @@ -1,106 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020-2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file autotune_attitude_control_params.c - * - * Parameters used by the attitude auto-tuner - * - * @author Mathieu Bresciani - */ - -/** - * Multicopter autotune module enable - * - * @boolean - * @group Autotune - */ -PARAM_DEFINE_INT32(MC_AT_EN, 0); - -/** - * Start the autotuning sequence - * - * WARNING: this will inject steps to the rate controller - * and can be dangerous. Only activate if you know what you - * are doing, and in a safe environment. - * - * Any motion of the remote stick will abord the signal - * injection and reset this parameter - * Best is to perform the identification in position or - * hold mode. - * Increase the amplitude of the injected signal using - * MC_AT_SYSID_AMP for more signal/noise ratio - * - * @boolean - * @group Autotune - */ -PARAM_DEFINE_INT32(MC_AT_START, 0); - -/** - * Amplitude of the injected signal - * - * @min 0.1 - * @max 6.0 - * @decimal 1 - * @group Autotune - */ -PARAM_DEFINE_FLOAT(MC_AT_SYSID_AMP, 0.7); - -/** - * Controls when to apply the new gains - * - * After the auto-tuning sequence is completed, - * a new set of gains is available and can be applied - * immediately or after landing. - * - * WARNING Applying the gains in air is dangerous as there is no - * guarantee that those new gains will be able to stabilize - * the drone properly. - * - * @value 0 Do not apply the new gains (logging only) - * @value 1 Apply the new gains after disarm - * @value 2 WARNING Apply the new gains in air - * @group Autotune - */ -PARAM_DEFINE_INT32(MC_AT_APPLY, 1); - -/** - * Desired angular rate closed-loop rise time - * - * @min 0.01 - * @max 0.5 - * @decimal 2 - * @unit s - * @group Autotune - */ -PARAM_DEFINE_FLOAT(MC_AT_RISE_TIME, 0.14); diff --git a/src/modules/mc_autotune_attitude_control/module.yaml b/src/modules/mc_autotune_attitude_control/module.yaml new file mode 100644 index 000000000000..b35e6f23ea5c --- /dev/null +++ b/src/modules/mc_autotune_attitude_control/module.yaml @@ -0,0 +1,47 @@ +module_name: mc_autotune_attitude_control +parameters: + - definitions: + MC_AT_APPLY: + default: 1 + description: + long: After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly. + short: Controls when to apply the new gains + type: enum + values: + 0: Do not apply the new gains (logging only) + 1: Apply the new gains after disarm + 2: WARNING Apply the new gains in air + volatile: false + MC_AT_EN: + default: 0 + description: + short: Multicopter autotune module enable + type: boolean + volatile: false + MC_AT_RISE_TIME: + decimal: 2 + default: 0.14 + description: + short: Desired angular rate closed-loop rise time + max: 0.5 + min: 0.01 + type: float + unit: s + volatile: false + MC_AT_START: + default: 0 + description: + long: 'WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abord the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio' + short: Start the autotuning sequence + type: boolean + volatile: false + MC_AT_SYSID_AMP: + decimal: 1 + default: 0.7 + description: + short: Amplitude of the injected signal + max: 6.0 + min: 0.1 + type: float + volatile: false + group: Autotune diff --git a/src/modules/mc_hover_thrust_estimator/CMakeLists.txt b/src/modules/mc_hover_thrust_estimator/CMakeLists.txt index 9504a18adddd..c49cc9ea1c49 100644 --- a/src/modules/mc_hover_thrust_estimator/CMakeLists.txt +++ b/src/modules/mc_hover_thrust_estimator/CMakeLists.txt @@ -44,6 +44,8 @@ px4_add_module( SRCS MulticopterHoverThrustEstimator.cpp MulticopterHoverThrustEstimator.hpp + MODULE_CONFIG + module.yaml DEPENDS hysteresis mathlib diff --git a/src/modules/mc_hover_thrust_estimator/hover_thrust_estimator_params.c b/src/modules/mc_hover_thrust_estimator/hover_thrust_estimator_params.c deleted file mode 100644 index fd46e23c9598..000000000000 --- a/src/modules/mc_hover_thrust_estimator/hover_thrust_estimator_params.c +++ /dev/null @@ -1,132 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file hover_thrust_estimator_params.c - * - * Parameters used by the hover thrust estimator - * - * @author Mathieu Bresciani - */ - -/** - * Hover thrust process noise - * - * Reduce to make the hover thrust estimate - * more stable, increase if the real hover thrust - * is expected to change quickly over time. - * - * @decimal 4 - * @min 0.0001 - * @max 1.0 - * @unit normalized_thrust/s - * @group Hover Thrust Estimator - */ -PARAM_DEFINE_FLOAT(HTE_HT_NOISE, 0.0036); - -/** - * Gate size for acceleration fusion - * - * Sets the number of standard deviations used - * by the innovation consistency test. - * - * @decimal 1 - * @min 1.0 - * @max 10.0 - * @unit SD - * @group Hover Thrust Estimator - */ -PARAM_DEFINE_FLOAT(HTE_ACC_GATE, 3.0); - -/** - * 1-sigma initial hover thrust uncertainty - * - * Sets the number of standard deviations used - * by the innovation consistency test. - * - * @decimal 3 - * @min 0.0 - * @max 1.0 - * @unit normalized_thrust - * @group Hover Thrust Estimator - */ -PARAM_DEFINE_FLOAT(HTE_HT_ERR_INIT, 0.1); - -/** - * Horizontal velocity threshold for sensitivity reduction - * - * Above this speed, the measurement noise is linearly increased - * to reduce the sensitivity of the estimator from biased measurement. - * - * Set to a low value on vehicles with large lifting surfaces. - * - * @decimal 1 - * @min 1.0 - * @max 20.0 - * @unit m/s - * @group Hover Thrust Estimator - */ -PARAM_DEFINE_FLOAT(HTE_VXY_THR, 10.0); - -/** - * Vertical velocity threshold for sensitivity reduction - * - * Above this speed, the measurement noise is linearly increased - * to reduce the sensitivity of the estimator from biased measurement. - * - * Set to a low value on vehicles affected by air drag when climbing or descending. - * - * @decimal 1 - * @min 1.0 - * @max 10.0 - * @unit m/s - * @group Hover Thrust Estimator - */ -PARAM_DEFINE_FLOAT(HTE_VZ_THR, 2.0); - -/** - * Max deviation from MPC_THR_HOVER - * - * Defines the range of the hover thrust estimate around MPC_THR_HOVER. - * A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. - * - * Set to a large value if the vehicle operates in varying physical conditions that - * affect the required hover thrust strongly (e.g. differently sized payloads). - * - * @decimal 2 - * @min 0.01 - * @max 0.4 - * @unit normalized_thrust - * @group Hover Thrust Estimator - */ -PARAM_DEFINE_FLOAT(HTE_THR_RANGE, 0.2); diff --git a/src/modules/mc_hover_thrust_estimator/module.yaml b/src/modules/mc_hover_thrust_estimator/module.yaml new file mode 100644 index 000000000000..0d740012aad1 --- /dev/null +++ b/src/modules/mc_hover_thrust_estimator/module.yaml @@ -0,0 +1,70 @@ +module_name: mc_hover_thrust_estimator +parameters: + - definitions: + HTE_ACC_GATE: + decimal: 1 + default: 3.0 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: Gate size for acceleration fusion + max: 10.0 + min: 1.0 + type: float + unit: SD + volatile: false + HTE_HT_ERR_INIT: + decimal: 3 + default: 0.1 + description: + long: Sets the number of standard deviations used by the innovation consistency test. + short: 1-sigma initial hover thrust uncertainty + max: 1.0 + min: 0.0 + type: float + unit: normalized_thrust + volatile: false + HTE_HT_NOISE: + decimal: 4 + default: 0.0036 + description: + long: Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time. + short: Hover thrust process noise + max: 1.0 + min: 0.0001 + type: float + unit: normalized_thrust/s + volatile: false + HTE_THR_RANGE: + decimal: 2 + default: 0.2 + description: + long: Defines the range of the hover thrust estimate around MPC_THR_HOVER. A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. Set to a large value if the vehicle operates in varying physical conditions that affect the required hover thrust strongly (e.g. differently sized payloads). + short: Max deviation from MPC_THR_HOVER + max: 0.4 + min: 0.01 + type: float + unit: normalized_thrust + volatile: false + HTE_VXY_THR: + decimal: 1 + default: 10.0 + description: + long: Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles with large lifting surfaces. + short: Horizontal velocity threshold for sensitivity reduction + max: 20.0 + min: 1.0 + type: float + unit: m/s + volatile: false + HTE_VZ_THR: + decimal: 1 + default: 2.0 + description: + long: Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles affected by air drag when climbing or descending. + short: Vertical velocity threshold for sensitivity reduction + max: 10.0 + min: 1.0 + type: float + unit: m/s + volatile: false + group: Hover Thrust Estimator diff --git a/src/modules/mc_pos_control/CMakeLists.txt b/src/modules/mc_pos_control/CMakeLists.txt index 49f61ac967e9..2abd266a1fc3 100644 --- a/src/modules/mc_pos_control/CMakeLists.txt +++ b/src/modules/mc_pos_control/CMakeLists.txt @@ -41,6 +41,8 @@ px4_add_module( SRCS MulticopterPositionControl.cpp MulticopterPositionControl.hpp + MODULE_CONFIG + module.yaml DEPENDS PositionControl Takeoff diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c deleted file mode 100644 index 25d094289c61..000000000000 --- a/src/modules/mc_pos_control/mc_pos_control_params.c +++ /dev/null @@ -1,878 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mc_pos_control_params.c - * Multicopter position controller parameters. - * - * @author Anton Babushkin - */ - -/** - * Minimum collective thrust in auto thrust control - * - * It's recommended to set it > 0 to avoid free fall with zero thrust. - * Note: Without airmode zero thrust leads to zero roll/pitch control authority. (see MC_AIRMODE) - * - * @unit norm - * @min 0.05 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.12f); - -/** - * Hover thrust - * - * Vertical thrust required to hover. - * This value is mapped to center stick for manual throttle control. - * With this value set to the thrust required to hover, transition - * from manual to Altitude or Position mode while hovering will occur with the - * throttle stick near center, which is then interpreted as (near) - * zero demand for vertical speed. - * - * This parameter is also important for the landing detection to work correctly. - * - * @unit norm - * @min 0.1 - * @max 0.8 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_THR_HOVER, 0.5f); - -/** - * Hover thrust source selector - * - * Set false to use the fixed parameter MPC_THR_HOVER - * Set true to use the value computed by the hover thrust estimator - * - * @boolean - * @group Multicopter Position Control - */ -PARAM_DEFINE_INT32(MPC_USE_HTE, 1); - -/** - * Thrust curve in Manual Mode - * - * This parameter defines how the throttle stick input is mapped to commanded thrust - * in Manual/Stabilized flight mode. - * - * In case the default is used ('Rescale to hover thrust'), the stick input is linearly - * rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER). - * - * Select 'No Rescale' to directly map the stick 1:1 to the output. This can be useful - * in case the hover thrust is very low and the default would lead to too much distortion - * (e.g. if hover thrust is set to 20%, 80% of the upper thrust range is squeezed into the - * upper half of the stick range). - * - * Note: In case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same. - * - * @value 0 Rescale to hover thrust - * @value 1 No Rescale - * @group Multicopter Position Control - */ -PARAM_DEFINE_INT32(MPC_THR_CURVE, 0); - -/** - * Horizontal thrust margin - * - * Margin that is kept for horizontal control when prioritizing vertical thrust. - * To avoid completely starving horizontal control with high vertical error. - * - * @unit norm - * @min 0.0 - * @max 0.5 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_THR_XY_MARG, 0.3f); - -/** - * Maximum thrust in auto thrust control - * - * Limit max allowed thrust - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_THR_MAX, 1.0f); - -/** - * Minimum manual thrust - * - * Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. - * With MC_AIRMODE set to 1, this can safely be set to 0. - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_MANTHR_MIN, 0.08f); - -/** - * Proportional gain for vertical position error - * - * @min 0.0 - * @max 1.5 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_P, 1.0f); - -/** - * Proportional gain for vertical velocity error - * - * defined as correction acceleration in m/s^2 per m/s velocity error - * - * @min 2.0 - * @max 15.0 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_VEL_P_ACC, 4.0f); - -/** - * Integral gain for vertical velocity error - * - * defined as correction acceleration in m/s^2 per m velocity integral - * - * Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. - * - * @min 0.2 - * @max 3.0 - * @decimal 3 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_VEL_I_ACC, 2.0f); - -/** - * Differential gain for vertical velocity error - * - * defined as correction acceleration in m/s^2 per m/s^2 velocity derivative - * - * @min 0.0 - * @max 2.0 - * @decimal 3 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_VEL_D_ACC, 0.0f); - -/** - * Automatic ascent velocity - * - * Ascent velocity in auto modes. - * For manual modes and offboard, see MPC_Z_VEL_MAX_UP - * - * @unit m/s - * @min 0.5 - * @max 8.0 - * @increment 0.1 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_V_AUTO_UP, 3.f); - -/** - * Maximum ascent velocity - * - * Ascent velocity in manual modes and offboard. - * For auto modes, see MPC_Z_V_AUTO_UP - * - * @unit m/s - * @min 0.5 - * @max 8.0 - * @increment 0.1 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX_UP, 3.f); - -/** - * Automatic descent velocity - * - * Descent velocity in auto modes. - * For manual modes and offboard, see MPC_Z_VEL_MAX_DN - * - * @unit m/s - * @min 0.5 - * @max 4.0 - * @increment 0.1 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_V_AUTO_DN, 1.f); - -/** - * Maximum descent velocity - * - * Descent velocity in manual modes and offboard. - * For auto modes, see MPC_Z_V_AUTO_DN - * - * @unit m/s - * @min 0.5 - * @max 4.0 - * @increment 0.1 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX_DN, 1.f); - -/** - * Proportional gain for horizontal position error - * - * @min 0.0 - * @max 2.0 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_P, 0.95f); - -/** - * Proportional gain for horizontal velocity error - * - * defined as correction acceleration in m/s^2 per m/s velocity error - * - * @min 1.2 - * @max 5.0 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_VEL_P_ACC, 1.8f); - -/** - * Integral gain for horizontal velocity error - * - * defined as correction acceleration in m/s^2 per m velocity integral - * Non-zero value allows to eliminate steady state errors in the presence of disturbances like wind. - * - * @min 0.0 - * @max 60.0 - * @decimal 3 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_VEL_I_ACC, 0.4f); - -/** - * Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - * - * defined as correction acceleration in m/s^2 per m/s^2 velocity derivative - * - * @min 0.1 - * @max 2.0 - * @decimal 3 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_VEL_D_ACC, 0.2f); - -/** - * Default horizontal velocity in mission - * - * Horizontal velocity used when flying autonomously in e.g. Missions, RTL, Goto. - * - * @unit m/s - * @min 3.0 - * @max 20.0 - * @increment 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_CRUISE, 5.0f); - -/** - * Proportional gain for horizontal trajectory position error - * - * @min 0.1 - * @max 1.0 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_TRAJ_P, 0.5f); - -/** - * Maximum horizontal error allowed by the trajectory generator - * - * The integration speed of the trajectory setpoint is linearly - * reduced with the horizontal position tracking error. When the - * error is above this parameter, the integration of the - * trajectory is stopped to wait for the drone. - * - * This value can be adjusted depending on the tracking - * capabilities of the vehicle. - * - * @min 0.1 - * @max 10.0 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_ERR_MAX, 2.0f); - -/** - * Maximum horizontal velocity setpoint in Position mode - * - * If velocity setpoint larger than MPC_XY_VEL_MAX is set, then - * the setpoint will be capped to MPC_XY_VEL_MAX - * - * The maximum sideways and backward speed can be set differently - * using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively. - * - * @unit m/s - * @min 3.0 - * @max 20.0 - * @increment 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_VEL_MANUAL, 10.0f); - -/** - * Maximum sideways velocity in Position mode - * - * If set to a negative value or larger than - * MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. - * - * @unit m/s - * @min -1.0 - * @max 20.0 - * @increment 0.1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_VEL_MAN_SIDE, -1.0f); - -/** - * Maximum backward velocity in Position mode - * - * If set to a negative value or larger than - * MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. - * - * @unit m/s - * @min -1.0 - * @max 20.0 - * @increment 0.1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_VEL_MAN_BACK, -1.0f); - -/** - * Maximum horizontal velocity - * - * Maximum horizontal velocity in AUTO mode. If higher speeds - * are commanded in a mission they will be capped to this velocity. - * - * @unit m/s - * @min 0.0 - * @max 20.0 - * @increment 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 12.0f); - -/** - * Maximum tilt angle in air - * - * Limits maximum tilt in AUTO and POSCTRL modes during flight. - * - * @unit deg - * @min 20.0 - * @max 89.0 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_TILTMAX_AIR, 45.0f); - -/** - * Maximum tilt during landing - * - * Limits maximum tilt angle on landing. - * - * @unit deg - * @min 10.0 - * @max 89.0 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_TILTMAX_LND, 12.0f); - -/** - * Landing descend rate - * - * @unit m/s - * @min 0.6 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 0.7f); - -/** - * Land crawl descend rate. Used below - * - * @unit m/s - * @min 0.3 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_LAND_CRWL, 0.3f); - -/** - * Enable user assisted descent speed for autonomous land routine. - * - * When enabled, descent speed will be: - * stick full up - 0 - * stick centered - MPC_LAND_SPEED - * stick full down - 2 * MPC_LAND_SPEED - * - * @min 0 - * @max 1 - * @value 0 Fixed descent speed of MPC_LAND_SPEED - * @value 1 User assisted descent speed - */ -PARAM_DEFINE_INT32(MPC_LAND_RC_HELP, 0); - -/** - * Takeoff climb rate - * - * @unit m/s - * @min 1 - * @max 5 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_TKO_SPEED, 1.5f); - -/** - * Maximal tilt angle in manual or altitude mode - * - * @unit deg - * @min 0.0 - * @max 90.0 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_MAN_TILT_MAX, 35.0f); - -/** - * Max manual yaw rate - * - * @unit deg/s - * @min 0.0 - * @max 400 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_MAN_Y_MAX, 150.0f); - -/** - * Manual yaw rate input filter time constant - * - * Setting this parameter to 0 disables the filter - * - * @unit s - * @min 0.0 - * @max 5.0 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_MAN_Y_TAU, 0.08f); - -/** - * Deadzone of sticks where position hold is enabled - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_HOLD_DZ, 0.1f); - -/** - * Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) - * - * @unit m/s - * @min 0.0 - * @max 3.0 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_HOLD_MAX_XY, 0.8f); - -/** - * Maximum vertical velocity for which position hold is enabled (use 0 to disable check) - * - * @unit m/s - * @min 0.0 - * @max 3.0 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_HOLD_MAX_Z, 0.6f); - -/** - * Low pass filter cut freq. for numerical velocity derivative - * - * @unit Hz - * @min 0.0 - * @max 10 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_VELD_LP, 5.0f); - -/** - * Maximum horizontal acceleration for auto mode and for manual mode - * - * MPC_POS_MODE - * 1 just deceleration - * 3 acceleration and deceleration - * 4 just acceleration - * - * @unit m/s^2 - * @min 2.0 - * @max 15.0 - * @increment 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_ACC_HOR_MAX, 5.0f); - -/** - * Acceleration for auto and for manual - * - * Note: In manual, this parameter is only used in MPC_POS_MODE 4. - * - * @unit m/s^2 - * @min 2.0 - * @max 15.0 - * @increment 1 - * @decimal 2 - * @group Multicopter Position Control - */ - -PARAM_DEFINE_FLOAT(MPC_ACC_HOR, 3.0f); - -/** - * Maximum vertical acceleration in velocity controlled modes upward - * - * @unit m/s^2 - * @min 2.0 - * @max 15.0 - * @increment 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_ACC_UP_MAX, 4.0f); - -/** - * Maximum vertical acceleration in velocity controlled modes down - * - * @unit m/s^2 - * @min 2.0 - * @max 15.0 - * @increment 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_ACC_DOWN_MAX, 3.0f); - -/** - * Maximum jerk limit - * - * Limit the maximum jerk of the vehicle (how fast the acceleration can change). - * A lower value leads to smoother vehicle motions, but it also limits its - * agility (how fast it can change directions or break). - * - * Setting this to the maximum value essentially disables the limit. - * - * Note: This is only used when MPC_POS_MODE is set to a smoothing mode 3 or 4. - * - * @unit m/s^3 - * @min 0.5 - * @max 500.0 - * @increment 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_JERK_MAX, 8.0f); - -/** - * Jerk limit in auto mode - * - * Limit the maximum jerk of the vehicle (how fast the acceleration can change). - * A lower value leads to smoother vehicle motions, but it also limits its - * agility. - * - * @unit m/s^3 - * @min 1.0 - * @max 80.0 - * @increment 1 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_JERK_AUTO, 4.0f); - -/** - * Altitude control mode. - * - * Set to 0 to control height relative to the earth frame origin. This origin may move up and down in - * flight due to sensor drift. - * Set to 1 to control height relative to estimated distance to ground. The vehicle will move up and down - * with terrain height variation. Requires a distance to ground sensor. The height controller will - * revert to using height above origin if the distance to ground estimate becomes invalid as indicated - * by the local_position.distance_bottom_valid message being false. - * Set to 2 to control height relative to ground (requires a distance sensor) when stationary and relative - * to earth frame origin when moving horizontally. - * The speed threshold is controlled by the MPC_HOLD_MAX_XY parameter. - * - * @min 0 - * @max 2 - * @value 0 Altitude following - * @value 1 Terrain following - * @value 2 Terrain hold - * @group Multicopter Position Control - */ -PARAM_DEFINE_INT32(MPC_ALT_MODE, 0); - -/** - * Manual position control stick exponential curve sensitivity - * - * The higher the value the less sensitivity the stick has around zero - * while still reaching the maximum value with full stick deflection. - * - * 0 Purely linear input curve (default) - * 1 Purely cubic input curve - * - * @min 0 - * @max 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_MAN_EXPO, 0.6f); - -/** - * Manual control stick vertical exponential curve - * - * The higher the value the less sensitivity the stick has around zero - * while still reaching the maximum value with full stick deflection. - * - * 0 Purely linear input curve (default) - * 1 Purely cubic input curve - * - * @min 0 - * @max 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_MAN_EXPO, 0.6f); - -/** - * Manual control stick yaw rotation exponential curve - * - * The higher the value the less sensitivity the stick has around zero - * while still reaching the maximum value with full stick deflection. - * - * 0 Purely linear input curve (default) - * 1 Purely cubic input curve - * - * @min 0 - * @max 1 - * @decimal 2 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_YAW_EXPO, 0.6f); - -/** - * Max yaw rate in auto mode - * - * Limit the rate of change of the yaw setpoint in autonomous mode - * to avoid large control output and mixer saturation. - * - * @unit deg/s - * @min 0.0 - * @max 360.0 - * @decimal 1 - * @increment 5 - * @group Multicopter Attitude Control - */ -PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 45.0f); - -/** - * Altitude for 1. step of slow landing (descend) - * - * Below this altitude descending velocity gets limited to a value - * between "MPC_Z_VEL_MAX_DN" (or "MPC_Z_V_AUTO_DN") and "MPC_LAND_SPEED" - * Value needs to be higher than "MPC_LAND_ALT2" - * - * @unit m - * @min 0 - * @max 122 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_LAND_ALT1, 10.0f); - -/** - * Altitude for 2. step of slow landing (landing) - * - * Below this altitude descending velocity gets - * limited to "MPC_LAND_SPEED" - * Value needs to be lower than "MPC_LAND_ALT1" - * - * @unit m - * @min 0 - * @max 122 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_LAND_ALT2, 5.0f); - -/** - * Altitude for 3. step of slow landing - * - * Below this altitude descending velocity gets - * limited to "MPC_LAND_CRWL", if LIDAR available. - * No effect if LIDAR not available - * - * @unit m - * @min 0 - * @max 122 - * @decimal 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_LAND_ALT3, 1.0f); - -/** - * Position control smooth takeoff ramp time constant - * - * Increasing this value will make automatic and manual takeoff slower. - * If it's too slow the drone might scratch the ground and tip over. - * A time constant of 0 disables the ramp - * - * @min 0 - * @max 5 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_TKO_RAMP_T, 3.0f); - -/** - * Manual-Position control sub-mode - * - * The supported sub-modes are: - * 0 Simple position control where sticks map directly to velocity setpoints - * without smoothing. Useful for velocity control tuning. - * 3 Smooth position control with maximum acceleration and jerk limits based on - * jerk optimized trajectory generator (different algorithm than 1). - * 4 Smooth position control where sticks map to acceleration and there's a virtual brake drag - * - * @value 0 Simple position control - * @value 3 Smooth position control (Jerk optimized) - * @value 4 Acceleration based input - * @group Multicopter Position Control - */ -PARAM_DEFINE_INT32(MPC_POS_MODE, 4); - -/** - * Yaw mode. - * - * Specifies the heading in Auto. - * - * @min 0 - * @max 4 - * @value 0 towards waypoint - * @value 1 towards home - * @value 2 away from home - * @value 3 along trajectory - * @value 4 towards waypoint (yaw first) - * @group Mission - */ -PARAM_DEFINE_INT32(MPC_YAW_MODE, 0); - -/** - * Responsiveness - * - * Changes the overall responsiveness of the vehicle. - * The higher the value, the faster the vehicle will react. - * - * If set to a value greater than zero, other parameters are automatically set (such as - * the acceleration or jerk limits). - * If set to a negative value, the existing individual parameters are used. - * - * @min -1 - * @max 1 - * @decimal 2 - * @increment 0.05 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(SYS_VEHICLE_RESP, -0.4f); - -/** - * Overall Horizonal Velocity Limit - * - * If set to a value greater than zero, other parameters are automatically set (such as - * MPC_XY_VEL_MAX or MPC_VEL_MANUAL). - * If set to a negative value, the existing individual parameters are used. - * - * @min -20 - * @max 20 - * @decimal 1 - * @increment 1 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_VEL_ALL, -10.0f); - -/** - * Overall Vertical Velocity Limit - * - * If set to a value greater than zero, other parameters are automatically set (such as - * MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). - * If set to a negative value, the existing individual parameters are used. - * - * @min -3 - * @max 8 - * @decimal 1 - * @increment 0.5 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_VEL_ALL, -3.0f); diff --git a/src/modules/mc_pos_control/module.yaml b/src/modules/mc_pos_control/module.yaml new file mode 100644 index 000000000000..ec72ff347b31 --- /dev/null +++ b/src/modules/mc_pos_control/module.yaml @@ -0,0 +1,650 @@ +module_name: mc_pos_control +parameters: + - definitions: + MPC_YAW_MODE: + default: 0 + description: + long: Specifies the heading in Auto. + short: Yaw mode + max: 4 + min: 0 + type: enum + values: + 0: towards waypoint + 1: towards home + 2: away from home + 3: along trajectory + 4: towards waypoint (yaw first) + volatile: false + group: Mission + - definitions: + MPC_YAWRAUTO_MAX: + decimal: 1 + default: 45.0 + description: + long: Limit the rate of change of the yaw setpoint in autonomous mode to avoid large control output and mixer saturation. + short: Max yaw rate in auto mode + increment: 5 + max: 360.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + group: Multicopter Attitude Control + - definitions: + MPC_ACC_DOWN_MAX: + decimal: 2 + default: 3.0 + description: + short: Maximum vertical acceleration in velocity controlled modes down + increment: 1 + max: 15.0 + min: 2.0 + type: float + unit: m/s^2 + volatile: false + MPC_ACC_HOR: + decimal: 2 + default: 3.0 + description: + long: 'Note: In manual, this parameter is only used in MPC_POS_MODE 4.' + short: Acceleration for auto and for manual + increment: 1 + max: 15.0 + min: 2.0 + type: float + unit: m/s^2 + volatile: false + MPC_ACC_HOR_MAX: + decimal: 2 + default: 5.0 + description: + long: MPC_POS_MODE 1 just deceleration 3 acceleration and deceleration 4 just acceleration + short: Maximum horizontal acceleration for auto mode and for manual mode + increment: 1 + max: 15.0 + min: 2.0 + type: float + unit: m/s^2 + volatile: false + MPC_ACC_UP_MAX: + decimal: 2 + default: 4.0 + description: + short: Maximum vertical acceleration in velocity controlled modes upward + increment: 1 + max: 15.0 + min: 2.0 + type: float + unit: m/s^2 + volatile: false + MPC_ALT_MODE: + default: 0 + description: + long: Set to 0 to control height relative to the earth frame origin. This origin may move up and down in flight due to sensor drift. Set to 1 to control height relative to estimated distance to ground. The vehicle will move up and down with terrain height variation. Requires a distance to ground sensor. The height controller will revert to using height above origin if the distance to ground estimate becomes invalid as indicated by the local_position.distance_bottom_valid message being false. Set to 2 to control height relative to ground (requires a distance sensor) when stationary and relative to earth frame origin when moving horizontally. The speed threshold is controlled by the MPC_HOLD_MAX_XY parameter. + short: Altitude control mode + max: 2 + min: 0 + type: enum + values: + 0: Altitude following + 1: Terrain following + 2: Terrain hold + volatile: false + MPC_HOLD_DZ: + decimal: 2 + default: 0.1 + description: + short: Deadzone of sticks where position hold is enabled + max: 1.0 + min: 0.0 + type: float + volatile: false + MPC_HOLD_MAX_XY: + decimal: 2 + default: 0.8 + description: + short: Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) + max: 3.0 + min: 0.0 + type: float + unit: m/s + volatile: false + MPC_HOLD_MAX_Z: + decimal: 2 + default: 0.6 + description: + short: Maximum vertical velocity for which position hold is enabled (use 0 to disable check) + max: 3.0 + min: 0.0 + type: float + unit: m/s + volatile: false + MPC_JERK_AUTO: + decimal: 1 + default: 4.0 + description: + long: Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility. + short: Jerk limit in auto mode + increment: 1 + max: 80.0 + min: 1.0 + type: float + unit: m/s^3 + volatile: false + MPC_JERK_MAX: + decimal: 2 + default: 8.0 + description: + long: 'Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility (how fast it can change directions or break). Setting this to the maximum value essentially disables the limit. Note: This is only used when MPC_POS_MODE is set to a smoothing mode 3 or 4.' + short: Maximum jerk limit + increment: 1 + max: 500.0 + min: 0.5 + type: float + unit: m/s^3 + volatile: false + MPC_LAND_ALT1: + decimal: 1 + default: 10.0 + description: + long: Below this altitude descending velocity gets limited to a value between "MPC_Z_VEL_MAX_DN" (or "MPC_Z_V_AUTO_DN") and "MPC_LAND_SPEED" Value needs to be higher than "MPC_LAND_ALT2" + short: Altitude for 1. step of slow landing (descend) + max: 122 + min: 0 + type: float + unit: m + volatile: false + MPC_LAND_ALT2: + decimal: 1 + default: 5.0 + description: + long: Below this altitude descending velocity gets limited to "MPC_LAND_SPEED" Value needs to be lower than "MPC_LAND_ALT1" + short: Altitude for 2. step of slow landing (landing) + max: 122 + min: 0 + type: float + unit: m + volatile: false + MPC_LAND_ALT3: + decimal: 1 + default: 1.0 + description: + long: Below this altitude descending velocity gets limited to "MPC_LAND_CRWL", if LIDAR available. No effect if LIDAR not available + short: Altitude for 3. step of slow landing + max: 122 + min: 0 + type: float + unit: m + volatile: false + MPC_LAND_CRWL: + decimal: 1 + default: 0.3 + description: + short: Land crawl descend rate. Used below + min: 0.3 + type: float + unit: m/s + volatile: false + MPC_LAND_SPEED: + decimal: 1 + default: 0.7 + description: + short: Landing descend rate + min: 0.6 + type: float + unit: m/s + volatile: false + MPC_MANTHR_MIN: + decimal: 2 + default: 0.08 + description: + long: Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. With MC_AIRMODE set to 1, this can safely be set to 0. + short: Minimum manual thrust + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + MPC_MAN_TILT_MAX: + decimal: 1 + default: 35.0 + description: + short: Maximal tilt angle in manual or altitude mode + max: 90.0 + min: 0.0 + type: float + unit: deg + volatile: false + MPC_MAN_Y_MAX: + decimal: 1 + default: 150.0 + description: + short: Max manual yaw rate + max: 400 + min: 0.0 + type: float + unit: deg/s + volatile: false + MPC_MAN_Y_TAU: + decimal: 2 + default: 0.08 + description: + long: Setting this parameter to 0 disables the filter + short: Manual yaw rate input filter time constant + max: 5.0 + min: 0.0 + type: float + unit: s + volatile: false + MPC_POS_MODE: + default: 4 + description: + long: 'The supported sub-modes are: 0 Simple position control where sticks map directly to velocity setpoints without smoothing. Useful for velocity control tuning. 3 Smooth position control with maximum acceleration and jerk limits based on jerk optimized trajectory generator (different algorithm than 1). 4 Smooth position control where sticks map to acceleration and there''s a virtual brake drag' + short: Manual-Position control sub-mode + type: enum + values: + 0: Simple position control + 3: Smooth position control (Jerk optimized) + 4: Acceleration based input + volatile: false + MPC_THR_CURVE: + default: 0 + description: + long: 'This parameter defines how the throttle stick input is mapped to commanded thrust in Manual/Stabilized flight mode. In case the default is used (''Rescale to hover thrust''), the stick input is linearly rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER). Select ''No Rescale'' to directly map the stick 1:1 to the output. This can be useful in case the hover thrust is very low and the default would lead to too much distortion (e.g. if hover thrust is set to 20%, 80% of the upper thrust range is squeezed into the upper half of the stick range). Note: In case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same.' + short: Thrust curve in Manual Mode + type: enum + values: + 0: Rescale to hover thrust + 1: No Rescale + volatile: false + MPC_THR_HOVER: + decimal: 2 + default: 0.5 + description: + long: Vertical thrust required to hover. This value is mapped to center stick for manual throttle control. With this value set to the thrust required to hover, transition from manual to Altitude or Position mode while hovering will occur with the throttle stick near center, which is then interpreted as (near) zero demand for vertical speed. This parameter is also important for the landing detection to work correctly. + short: Hover thrust + increment: 0.01 + max: 0.8 + min: 0.1 + type: float + unit: norm + volatile: false + MPC_THR_MAX: + decimal: 2 + default: 1.0 + description: + long: Limit max allowed thrust + short: Maximum thrust in auto thrust control + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + MPC_THR_MIN: + decimal: 2 + default: 0.12 + description: + long: 'It''s recommended to set it > 0 to avoid free fall with zero thrust. Note: Without airmode zero thrust leads to zero roll/pitch control authority. (see MC_AIRMODE)' + short: Minimum collective thrust in auto thrust control + increment: 0.01 + max: 1.0 + min: 0.05 + type: float + unit: norm + volatile: false + MPC_THR_XY_MARG: + decimal: 2 + default: 0.3 + description: + long: Margin that is kept for horizontal control when prioritizing vertical thrust. To avoid completely starving horizontal control with high vertical error. + short: Horizontal thrust margin + increment: 0.01 + max: 0.5 + min: 0.0 + type: float + unit: norm + volatile: false + MPC_TILTMAX_AIR: + decimal: 1 + default: 45.0 + description: + long: Limits maximum tilt in AUTO and POSCTRL modes during flight. + short: Maximum tilt angle in air + max: 89.0 + min: 20.0 + type: float + unit: deg + volatile: false + MPC_TILTMAX_LND: + decimal: 1 + default: 12.0 + description: + long: Limits maximum tilt angle on landing. + short: Maximum tilt during landing + max: 89.0 + min: 10.0 + type: float + unit: deg + volatile: false + MPC_TKO_RAMP_T: + default: 3.0 + description: + long: Increasing this value will make automatic and manual takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp + short: Position control smooth takeoff ramp time constant + max: 5 + min: 0 + type: float + volatile: false + MPC_TKO_SPEED: + decimal: 2 + default: 1.5 + description: + short: Takeoff climb rate + max: 5 + min: 1 + type: float + unit: m/s + volatile: false + MPC_USE_HTE: + default: 1 + description: + long: Set false to use the fixed parameter MPC_THR_HOVER Set true to use the value computed by the hover thrust estimator + short: Hover thrust source selector + type: boolean + volatile: false + MPC_VELD_LP: + decimal: 2 + default: 5.0 + description: + short: Low pass filter cut freq. for numerical velocity derivative + max: 10 + min: 0.0 + type: float + unit: Hz + volatile: false + MPC_VEL_MANUAL: + decimal: 2 + default: 10.0 + description: + long: If velocity setpoint larger than MPC_XY_VEL_MAX is set, then the setpoint will be capped to MPC_XY_VEL_MAX The maximum sideways and backward speed can be set differently using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively. + short: Maximum horizontal velocity setpoint in Position mode + increment: 1 + max: 20.0 + min: 3.0 + type: float + unit: m/s + volatile: false + MPC_VEL_MAN_BACK: + decimal: 2 + default: -1.0 + description: + long: If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. + short: Maximum backward velocity in Position mode + increment: 0.1 + max: 20.0 + min: -1.0 + type: float + unit: m/s + volatile: false + MPC_VEL_MAN_SIDE: + decimal: 2 + default: -1.0 + description: + long: If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. + short: Maximum sideways velocity in Position mode + increment: 0.1 + max: 20.0 + min: -1.0 + type: float + unit: m/s + volatile: false + MPC_XY_CRUISE: + decimal: 2 + default: 5.0 + description: + long: Horizontal velocity used when flying autonomously in e.g. Missions, RTL, Goto. + short: Default horizontal velocity in mission + increment: 1 + max: 20.0 + min: 3.0 + type: float + unit: m/s + volatile: false + MPC_XY_ERR_MAX: + decimal: 1 + default: 2.0 + description: + long: The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle. + short: Maximum horizontal error allowed by the trajectory generator + max: 10.0 + min: 0.1 + type: float + volatile: false + MPC_XY_MAN_EXPO: + decimal: 2 + default: 0.6 + description: + long: The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve + short: Manual position control stick exponential curve sensitivity + max: 1 + min: 0 + type: float + volatile: false + MPC_XY_P: + decimal: 2 + default: 0.95 + description: + short: Proportional gain for horizontal position error + max: 2.0 + min: 0.0 + type: float + volatile: false + MPC_XY_TRAJ_P: + decimal: 1 + default: 0.5 + description: + short: Proportional gain for horizontal trajectory position error + max: 1.0 + min: 0.1 + type: float + volatile: false + MPC_XY_VEL_ALL: + decimal: 1 + default: -10.0 + description: + long: If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used. + short: Overall Horizonal Velocity Limit + increment: 1 + max: 20 + min: -20 + type: float + volatile: false + MPC_XY_VEL_D_ACC: + decimal: 3 + default: 0.2 + description: + long: Small values help reduce fast oscillations. If value is too big oscillations will appear again. Defined as correction acceleration in m/s^2 per m/s^2 velocity derivative + short: Differential gain for horizontal velocity error. + max: 2.0 + min: 0.1 + type: float + volatile: false + MPC_XY_VEL_I_ACC: + decimal: 3 + default: 0.4 + description: + long: defined as correction acceleration in m/s^2 per m velocity integral Non-zero value allows to eliminate steady state errors in the presence of disturbances like wind. + short: Integral gain for horizontal velocity error + max: 60.0 + min: 0.0 + type: float + volatile: false + MPC_XY_VEL_MAX: + decimal: 2 + default: 12.0 + description: + long: Maximum horizontal velocity in AUTO mode. If higher speeds are commanded in a mission they will be capped to this velocity. + short: Maximum horizontal velocity + increment: 1 + max: 20.0 + min: 0.0 + type: float + unit: m/s + volatile: false + MPC_XY_VEL_P_ACC: + decimal: 2 + default: 1.8 + description: + long: defined as correction acceleration in m/s^2 per m/s velocity error + short: Proportional gain for horizontal velocity error + max: 5.0 + min: 1.2 + type: float + volatile: false + MPC_YAW_EXPO: + decimal: 2 + default: 0.6 + description: + long: The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve + short: Manual control stick yaw rotation exponential curve + max: 1 + min: 0 + type: float + volatile: false + MPC_Z_MAN_EXPO: + decimal: 2 + default: 0.6 + description: + long: The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve + short: Manual control stick vertical exponential curve + max: 1 + min: 0 + type: float + volatile: false + MPC_Z_P: + decimal: 2 + default: 1.0 + description: + short: Proportional gain for vertical position error + max: 1.5 + min: 0.0 + type: float + volatile: false + MPC_Z_VEL_ALL: + decimal: 1 + default: -3.0 + description: + long: If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used. + short: Overall Vertical Velocity Limit + increment: 0.5 + max: 8 + min: -3 + type: float + volatile: false + MPC_Z_VEL_D_ACC: + decimal: 3 + default: 0.0 + description: + long: defined as correction acceleration in m/s^2 per m/s^2 velocity derivative + short: Differential gain for vertical velocity error + max: 2.0 + min: 0.0 + type: float + volatile: false + MPC_Z_VEL_I_ACC: + decimal: 3 + default: 2.0 + description: + long: defined as correction acceleration in m/s^2 per m velocity integral Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. + short: Integral gain for vertical velocity error + max: 3.0 + min: 0.2 + type: float + volatile: false + MPC_Z_VEL_MAX_DN: + decimal: 1 + default: 1.0 + description: + long: Descent velocity in manual modes and offboard. For auto modes, see MPC_Z_V_AUTO_DN + short: Maximum descent velocity + increment: 0.1 + max: 4.0 + min: 0.5 + type: float + unit: m/s + volatile: false + MPC_Z_VEL_MAX_UP: + decimal: 1 + default: 3.0 + description: + long: Ascent velocity in manual modes and offboard. For auto modes, see MPC_Z_V_AUTO_UP + short: Maximum ascent velocity + increment: 0.1 + max: 8.0 + min: 0.5 + type: float + unit: m/s + volatile: false + MPC_Z_VEL_P_ACC: + decimal: 2 + default: 4.0 + description: + long: defined as correction acceleration in m/s^2 per m/s velocity error + short: Proportional gain for vertical velocity error + max: 15.0 + min: 2.0 + type: float + volatile: false + MPC_Z_V_AUTO_DN: + decimal: 1 + default: 1.0 + description: + long: Descent velocity in auto modes. For manual modes and offboard, see MPC_Z_VEL_MAX_DN + short: Automatic descent velocity + increment: 0.1 + max: 4.0 + min: 0.5 + type: float + unit: m/s + volatile: false + MPC_Z_V_AUTO_UP: + decimal: 1 + default: 3.0 + description: + long: Ascent velocity in auto modes. For manual modes and offboard, see MPC_Z_VEL_MAX_UP + short: Automatic ascent velocity + increment: 0.1 + max: 8.0 + min: 0.5 + type: float + unit: m/s + volatile: false + SYS_VEHICLE_RESP: + decimal: 2 + default: -0.4 + description: + long: Changes the overall responsiveness of the vehicle. The higher the value, the faster the vehicle will react. If set to a value greater than zero, other parameters are automatically set (such as the acceleration or jerk limits). If set to a negative value, the existing individual parameters are used. + short: Responsiveness + increment: 0.05 + max: 1 + min: -1 + type: float + volatile: false + group: Multicopter Position Control + - definitions: + MPC_LAND_RC_HELP: + default: 0 + description: + long: 'When enabled, descent speed will be: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED' + short: Enable user assisted descent speed for autonomous land routine + max: 1 + min: 0 + type: enum + values: + 0: Fixed descent speed of MPC_LAND_SPEED + 1: User assisted descent speed + volatile: false + group: Miscellaneous diff --git a/src/modules/mc_rate_control/CMakeLists.txt b/src/modules/mc_rate_control/CMakeLists.txt index 758d56b7c88a..d835e2a9f67d 100644 --- a/src/modules/mc_rate_control/CMakeLists.txt +++ b/src/modules/mc_rate_control/CMakeLists.txt @@ -41,6 +41,8 @@ px4_add_module( SRCS MulticopterRateControl.cpp MulticopterRateControl.hpp + MODULE_CONFIG + module.yaml DEPENDS circuit_breaker mathlib diff --git a/src/modules/mc_rate_control/mc_rate_control_params.c b/src/modules/mc_rate_control/mc_rate_control_params.c deleted file mode 100644 index 4bc092db601d..000000000000 --- a/src/modules/mc_rate_control/mc_rate_control_params.c +++ /dev/null @@ -1,400 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mc_rate_control_params.c - * Parameters for multicopter attitude controller. - * - * @author Lorenz Meier - * @author Anton Babushkin - */ - -/** - * Roll rate P gain - * - * Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. - * - * @min 0.01 - * @max 0.5 - * @decimal 3 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ROLLRATE_P, 0.15f); - -/** - * Roll rate I gain - * - * Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - * - * @min 0.0 - * @decimal 3 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ROLLRATE_I, 0.2f); - -/** - * Roll rate integrator limit - * - * Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. - * - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_RR_INT_LIM, 0.30f); - -/** - * Roll rate D gain - * - * Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - * - * @min 0.0 - * @max 0.01 - * @decimal 4 - * @increment 0.0005 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ROLLRATE_D, 0.003f); - -/** - * Roll rate feedforward - * - * Improves tracking performance. - * - * @min 0.0 - * @decimal 4 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ROLLRATE_FF, 0.0f); - -/** - * Roll rate controller gain - * - * Global gain of the controller. - * - * This gain scales the P, I and D terms of the controller: - * output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error - * + MC_ROLLRATE_I * error_integral - * + MC_ROLLRATE_D * error_derivative) - * Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. - * Set MC_ROLLRATE_K=1 to implement a PID in the parallel form. - * - * @min 0.01 - * @max 5.0 - * @decimal 4 - * @increment 0.0005 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ROLLRATE_K, 1.0f); - -/** - * Pitch rate P gain - * - * Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. - * - * @min 0.01 - * @max 0.6 - * @decimal 3 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_PITCHRATE_P, 0.15f); - -/** - * Pitch rate I gain - * - * Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - * - * @min 0.0 - * @decimal 3 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_PITCHRATE_I, 0.2f); - -/** - * Pitch rate integrator limit - * - * Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. - * - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_PR_INT_LIM, 0.30f); - -/** - * Pitch rate D gain - * - * Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - * - * @min 0.0 - * @decimal 4 - * @increment 0.0005 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_PITCHRATE_D, 0.003f); - -/** - * Pitch rate feedforward - * - * Improves tracking performance. - * - * @min 0.0 - * @decimal 4 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_PITCHRATE_FF, 0.0f); - -/** - * Pitch rate controller gain - * - * Global gain of the controller. - * - * This gain scales the P, I and D terms of the controller: - * output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error - * + MC_PITCHRATE_I * error_integral - * + MC_PITCHRATE_D * error_derivative) - * Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. - * Set MC_PITCHRATE_K=1 to implement a PID in the parallel form. - * - * @min 0.01 - * @max 5.0 - * @decimal 4 - * @increment 0.0005 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_PITCHRATE_K, 1.0f); - -/** - * Yaw rate P gain - * - * Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. - * - * @min 0.0 - * @max 0.6 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.2f); - -/** - * Yaw rate I gain - * - * Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - * - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.1f); - -/** - * Yaw rate integrator limit - * - * Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. - * - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_YR_INT_LIM, 0.30f); - -/** - * Yaw rate D gain - * - * Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - * - * @min 0.0 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f); - -/** - * Yaw rate feedforward - * - * Improves tracking performance. - * - * @min 0.0 - * @decimal 4 - * @increment 0.01 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_YAWRATE_FF, 0.0f); - -/** - * Yaw rate controller gain - * - * Global gain of the controller. - * - * This gain scales the P, I and D terms of the controller: - * output = MC_YAWRATE_K * (MC_YAWRATE_P * error - * + MC_YAWRATE_I * error_integral - * + MC_YAWRATE_D * error_derivative) - * Set MC_YAWRATE_P=1 to implement a PID in the ideal form. - * Set MC_YAWRATE_K=1 to implement a PID in the parallel form. - * - * @min 0.0 - * @max 5.0 - * @decimal 4 - * @increment 0.0005 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_YAWRATE_K, 1.0f); - -/** - * Max acro roll rate - * - * default: 2 turns per second - * - * @unit deg/s - * @min 0.0 - * @max 1800.0 - * @decimal 1 - * @increment 5 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ACRO_R_MAX, 720.0f); - -/** - * Max acro pitch rate - * - * default: 2 turns per second - * - * @unit deg/s - * @min 0.0 - * @max 1800.0 - * @decimal 1 - * @increment 5 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 720.0f); - -/** - * Max acro yaw rate - * - * default 1.5 turns per second - * - * @unit deg/s - * @min 0.0 - * @max 1800.0 - * @decimal 1 - * @increment 5 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ACRO_Y_MAX, 540.0f); - -/** - * Acro mode Expo factor for Roll and Pitch. - * - * Exponential factor for tuning the input curve shape. - * - * 0 Purely linear input curve - * 1 Purely cubic input curve - * - * @min 0 - * @max 1 - * @decimal 2 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ACRO_EXPO, 0.69f); - -/** - * Acro mode Expo factor for Yaw. - * - * Exponential factor for tuning the input curve shape. - * - * 0 Purely linear input curve - * 1 Purely cubic input curve - * - * @min 0 - * @max 1 - * @decimal 2 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ACRO_EXPO_Y, 0.69f); - -/** - * Acro mode SuperExpo factor for Roll and Pitch. - * - * SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. - * - * 0 Pure Expo function - * 0.7 resonable shape enhancement for intuitive stick feel - * 0.95 very strong bent input curve only near maxima have effect - * - * @min 0 - * @max 0.95 - * @decimal 2 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPO, 0.7f); - -/** - * Acro mode SuperExpo factor for Yaw. - * - * SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. - * - * 0 Pure Expo function - * 0.7 resonable shape enhancement for intuitive stick feel - * 0.95 very strong bent input curve only near maxima have effect - * - * @min 0 - * @max 0.95 - * @decimal 2 - * @group Multicopter Rate Control - */ -PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPOY, 0.7f); - -/** - * Battery power level scaler - * - * This compensates for voltage drop of the battery over time by attempting to - * normalize performance across the operating range of the battery. The copter - * should constantly behave as if it was fully charged with reduced max acceleration - * at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, - * it will still be 0.5 at 60% battery. - * - * @boolean - * @group Multicopter Rate Control - */ -PARAM_DEFINE_INT32(MC_BAT_SCALE_EN, 0); diff --git a/src/modules/mc_rate_control/module.yaml b/src/modules/mc_rate_control/module.yaml new file mode 100644 index 000000000000..ef559b193d2e --- /dev/null +++ b/src/modules/mc_rate_control/module.yaml @@ -0,0 +1,272 @@ +module_name: mc_rate_control +parameters: + - definitions: + MC_ACRO_EXPO: + decimal: 2 + default: 0.69 + description: + long: Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve + short: Acro mode Expo factor for Roll and Pitch + max: 1 + min: 0 + type: float + volatile: false + MC_ACRO_EXPO_Y: + decimal: 2 + default: 0.69 + description: + long: Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve + short: Acro mode Expo factor for Yaw + max: 1 + min: 0 + type: float + volatile: false + MC_ACRO_P_MAX: + decimal: 1 + default: 720.0 + description: + long: 'default: 2 turns per second' + short: Max acro pitch rate + increment: 5 + max: 1800.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + MC_ACRO_R_MAX: + decimal: 1 + default: 720.0 + description: + long: 'default: 2 turns per second' + short: Max acro roll rate + increment: 5 + max: 1800.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + MC_ACRO_SUPEXPO: + decimal: 2 + default: 0.7 + description: + long: SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect + short: Acro mode SuperExpo factor for Roll and Pitch + max: 0.95 + min: 0 + type: float + volatile: false + MC_ACRO_SUPEXPOY: + decimal: 2 + default: 0.7 + description: + long: SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect + short: Acro mode SuperExpo factor for Yaw + max: 0.95 + min: 0 + type: float + volatile: false + MC_ACRO_Y_MAX: + decimal: 1 + default: 540.0 + description: + long: default 1.5 turns per second + short: Max acro yaw rate + increment: 5 + max: 1800.0 + min: 0.0 + type: float + unit: deg/s + volatile: false + MC_BAT_SCALE_EN: + default: 0 + description: + long: This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. + short: Battery power level scaler + type: boolean + volatile: false + MC_PITCHRATE_D: + decimal: 4 + default: 0.003 + description: + long: Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + short: Pitch rate D gain + increment: 0.0005 + min: 0.0 + type: float + volatile: false + MC_PITCHRATE_FF: + decimal: 4 + default: 0.0 + description: + long: Improves tracking performance. + short: Pitch rate feedforward + min: 0.0 + type: float + volatile: false + MC_PITCHRATE_I: + decimal: 3 + default: 0.2 + description: + long: Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + short: Pitch rate I gain + increment: 0.01 + min: 0.0 + type: float + volatile: false + MC_PITCHRATE_K: + decimal: 4 + default: 1.0 + description: + long: 'Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error + MC_PITCHRATE_I * error_integral + MC_PITCHRATE_D * error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form.' + short: Pitch rate controller gain + increment: 0.0005 + max: 5.0 + min: 0.01 + type: float + volatile: false + MC_PITCHRATE_P: + decimal: 3 + default: 0.15 + description: + long: Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. + short: Pitch rate P gain + increment: 0.01 + max: 0.6 + min: 0.01 + type: float + volatile: false + MC_PR_INT_LIM: + decimal: 2 + default: 0.3 + description: + long: Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. + short: Pitch rate integrator limit + increment: 0.01 + min: 0.0 + type: float + volatile: false + MC_ROLLRATE_D: + decimal: 4 + default: 0.003 + description: + long: Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + short: Roll rate D gain + increment: 0.0005 + max: 0.01 + min: 0.0 + type: float + volatile: false + MC_ROLLRATE_FF: + decimal: 4 + default: 0.0 + description: + long: Improves tracking performance. + short: Roll rate feedforward + min: 0.0 + type: float + volatile: false + MC_ROLLRATE_I: + decimal: 3 + default: 0.2 + description: + long: Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + short: Roll rate I gain + increment: 0.01 + min: 0.0 + type: float + volatile: false + MC_ROLLRATE_K: + decimal: 4 + default: 1.0 + description: + long: 'Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error + MC_ROLLRATE_I * error_integral + MC_ROLLRATE_D * error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form.' + short: Roll rate controller gain + increment: 0.0005 + max: 5.0 + min: 0.01 + type: float + volatile: false + MC_ROLLRATE_P: + decimal: 3 + default: 0.15 + description: + long: Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. + short: Roll rate P gain + increment: 0.01 + max: 0.5 + min: 0.01 + type: float + volatile: false + MC_RR_INT_LIM: + decimal: 2 + default: 0.3 + description: + long: Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. + short: Roll rate integrator limit + increment: 0.01 + min: 0.0 + type: float + volatile: false + MC_YAWRATE_D: + decimal: 2 + default: 0.0 + description: + long: Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + short: Yaw rate D gain + increment: 0.01 + min: 0.0 + type: float + volatile: false + MC_YAWRATE_FF: + decimal: 4 + default: 0.0 + description: + long: Improves tracking performance. + short: Yaw rate feedforward + increment: 0.01 + min: 0.0 + type: float + volatile: false + MC_YAWRATE_I: + decimal: 2 + default: 0.1 + description: + long: Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + short: Yaw rate I gain + increment: 0.01 + min: 0.0 + type: float + volatile: false + MC_YAWRATE_K: + decimal: 4 + default: 1.0 + description: + long: 'Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K * (MC_YAWRATE_P * error + MC_YAWRATE_I * error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form.' + short: Yaw rate controller gain + increment: 0.0005 + max: 5.0 + min: 0.0 + type: float + volatile: false + MC_YAWRATE_P: + decimal: 2 + default: 0.2 + description: + long: Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. + short: Yaw rate P gain + increment: 0.01 + max: 0.6 + min: 0.0 + type: float + volatile: false + MC_YR_INT_LIM: + decimal: 2 + default: 0.3 + description: + long: Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. + short: Yaw rate integrator limit + increment: 0.01 + min: 0.0 + type: float + volatile: false + group: Multicopter Rate Control diff --git a/src/modules/navigator/CMakeLists.txt b/src/modules/navigator/CMakeLists.txt index ce5abd72bd28..fd375a996c32 100644 --- a/src/modules/navigator/CMakeLists.txt +++ b/src/modules/navigator/CMakeLists.txt @@ -49,6 +49,8 @@ px4_add_module( mission_feasibility_checker.cpp geofence.cpp vtol_takeoff.cpp + MODULE_CONFIG + module.yaml DEPENDS geo geofence_breach_avoidance diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c deleted file mode 100644 index 129aeb27747d..000000000000 --- a/src/modules/navigator/geofence_params.c +++ /dev/null @@ -1,140 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file geofence_params.c - * - * Parameters for geofence - * - * @author Thomas Gubler - */ - -/* - * Geofence parameters, accessible via MAVLink - */ - -/** - * Geofence violation action. - * - * Note: Setting this value to 4 enables flight termination, - * which will kill the vehicle on violation of the fence. - * - * @min 0 - * @max 5 - * @value 0 None - * @value 1 Warning - * @value 2 Hold mode - * @value 3 Return mode - * @value 4 Terminate - * @value 5 Land mode - * @group Geofence - */ -PARAM_DEFINE_INT32(GF_ACTION, 2); - -/** - * Geofence altitude mode - * - * Select which altitude (AMSL) source should be used for geofence calculations. - * - * @min 0 - * @max 1 - * @value 0 Autopilot estimator global position altitude (GPS) - * @value 1 Raw barometer altitude (assuming standard atmospheric pressure) - * @group Geofence - */ -PARAM_DEFINE_INT32(GF_ALTMODE, 0); - -/** - * Geofence source - * - * Select which position source should be used. Selecting GPS instead of global position makes sure that there is - * no dependence on the position estimator - * 0 = global position, 1 = GPS - * - * @min 0 - * @max 1 - * @value 0 GPOS - * @value 1 GPS - * @group Geofence - */ -PARAM_DEFINE_INT32(GF_SOURCE, 0); - -/** - * Geofence counter limit - * - * Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered - * - * @min -1 - * @max 10 - * @increment 1 - * @group Geofence - */ -PARAM_DEFINE_INT32(GF_COUNT, -1); - -/** - * Max horizontal distance in meters. - * - * Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. - * - * @unit m - * @min 0 - * @max 10000 - * @increment 1 - * @group Geofence - */ -PARAM_DEFINE_FLOAT(GF_MAX_HOR_DIST, 0); - -/** - * Max vertical distance in meters. - * - * Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. - * - * @unit m - * @min 0 - * @max 10000 - * @increment 1 - * @group Geofence - */ -PARAM_DEFINE_FLOAT(GF_MAX_VER_DIST, 0); - -/** - * Use Pre-emptive geofence triggering - * - * Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory - * would result in a breach happening before the vehicle can make evasive maneuvers. - * The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). - * - * @boolean - * @group Geofence - */ -PARAM_DEFINE_INT32(GF_PREDICT, 1); diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c deleted file mode 100644 index 3d647d224bd5..000000000000 --- a/src/modules/navigator/mission_params.c +++ /dev/null @@ -1,158 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mission_params.c - * - * Parameters for mission. - * - * @author Julian Oes - */ - -/* - * Mission parameters, accessible via MAVLink - */ - -/** - * Take-off altitude - * - * This is the minimum altitude the system will take off to. - * - * @unit m - * @min 0 - * @max 80 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 2.5f); - -/** - * Take-off waypoint required - * - * If set, the mission feasibility checker will check for a takeoff waypoint on the mission. - * - * @boolean - * @group Mission - */ -PARAM_DEFINE_INT32(MIS_TAKEOFF_REQ, 0); - -/** - * Minimum Loiter altitude - * - * This is the minimum altitude the system will always obey. The intent is to stay out of ground effect. - * set to -1, if there shouldn't be a minimum loiter altitude - * - * @unit m - * @min -1 - * @max 80 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_LTRMIN_ALT, -1.0f); - -/** - * Maximal horizontal distance from home to first waypoint - * - * Failsafe check to prevent running mission stored from previous flight at a new takeoff location. - * Set a value of zero or less to disable. The mission will not be started if the current - * waypoint is more distant than MIS_DIST_1WP from the home position. - * - * @unit m - * @min 0 - * @max 10000 - * @decimal 1 - * @increment 100 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 900); - -/** - * Maximal horizontal distance between waypoint - * - * Failsafe check to prevent running missions which are way too big. - * Set a value of zero or less to disable. The mission will not be started if any distance between - * two subsequent waypoints is greater than MIS_DIST_WPS. - * - * @unit m - * @min 0 - * @max 10000 - * @decimal 1 - * @increment 100 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_DIST_WPS, 900); - -/** -* Enable yaw control of the mount. (Only affects multicopters and ROI mission items) -* -* If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. -* If disabled, the vehicle will yaw towards the ROI. -* -* @value 0 Disable -* @value 1 Enable -* @min 0 -* @max 1 -* @group Mission -*/ -PARAM_DEFINE_INT32(MIS_MNT_YAW_CTL, 0); - -/** - * Time in seconds we wait on reaching target heading at a waypoint if it is forced. - * - * If set > 0 it will ignore the target heading for normal waypoint acceptance. If the - * waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. - * Mainly useful for VTOLs that have less yaw authority and might not reach target - * yaw in wind. Disabled by default. - * - * @unit s - * @min -1 - * @max 20 - * @decimal 1 - * @increment 1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_YAW_TMT, -1.0f); - -/** - * Max yaw error in degrees needed for waypoint heading acceptance. - * - * @unit deg - * @min 0 - * @max 90 - * @decimal 1 - * @increment 1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(MIS_YAW_ERR, 12.0f); diff --git a/src/modules/navigator/module.yaml b/src/modules/navigator/module.yaml new file mode 100644 index 000000000000..a080fddf1300 --- /dev/null +++ b/src/modules/navigator/module.yaml @@ -0,0 +1,530 @@ +module_name: navigator +parameters: + - definitions: + GF_ACTION: + default: 2 + description: + long: 'Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence.' + short: Geofence violation action + max: 5 + min: 0 + type: enum + values: + 0: None + 1: Warning + 2: Hold mode + 3: Return mode + 4: Terminate + 5: Land mode + volatile: false + GF_ALTMODE: + default: 0 + description: + long: Select which altitude (AMSL) source should be used for geofence calculations. + short: Geofence altitude mode + max: 1 + min: 0 + type: enum + values: + 0: Autopilot estimator global position altitude (GPS) + 1: Raw barometer altitude (assuming standard atmospheric pressure) + volatile: false + GF_COUNT: + default: -1 + description: + long: Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered + short: Geofence counter limit + increment: 1 + max: 10 + min: -1 + type: int32 + volatile: false + GF_MAX_HOR_DIST: + default: 0 + description: + long: Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. + short: Max horizontal distance in meters + increment: 1 + max: 10000 + min: 0 + type: float + unit: m + volatile: false + GF_MAX_VER_DIST: + default: 0 + description: + long: Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. + short: Max vertical distance in meters + increment: 1 + max: 10000 + min: 0 + type: float + unit: m + volatile: false + GF_PREDICT: + default: 1 + description: + long: Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). + short: Use Pre-emptive geofence triggering + type: boolean + volatile: false + GF_SOURCE: + default: 0 + description: + long: Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS + short: Geofence source + max: 1 + min: 0 + type: enum + values: + 0: GPOS + 1: GPS + volatile: false + group: Geofence + - definitions: + MIS_DIST_1WP: + decimal: 1 + default: 900 + description: + long: Failsafe check to prevent running mission stored from previous flight at a new takeoff location. Set a value of zero or less to disable. The mission will not be started if the current waypoint is more distant than MIS_DIST_1WP from the home position. + short: Maximal horizontal distance from home to first waypoint + increment: 100 + max: 10000 + min: 0 + type: float + unit: m + volatile: false + MIS_DIST_WPS: + decimal: 1 + default: 900 + description: + long: Failsafe check to prevent running missions which are way too big. Set a value of zero or less to disable. The mission will not be started if any distance between two subsequent waypoints is greater than MIS_DIST_WPS. + short: Maximal horizontal distance between waypoint + increment: 100 + max: 10000 + min: 0 + type: float + unit: m + volatile: false + MIS_LTRMIN_ALT: + decimal: 1 + default: -1.0 + description: + long: This is the minimum altitude the system will always obey. The intent is to stay out of ground effect. set to -1, if there shouldn't be a minimum loiter altitude + short: Minimum Loiter altitude + increment: 0.5 + max: 80 + min: -1 + type: float + unit: m + volatile: false + MIS_MNT_YAW_CTL: + default: 0 + description: + long: Only effects multicopters and ROI mission items. If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI. + short: Enable yaw control of the mount. + max: 1 + min: 0 + type: enum + values: + 0: Disable + 1: Enable + volatile: false + MIS_TAKEOFF_ALT: + decimal: 1 + default: 2.5 + description: + long: This is the minimum altitude the system will take off to. + short: Take-off altitude + increment: 0.5 + max: 80 + min: 0 + type: float + unit: m + volatile: false + MIS_TAKEOFF_REQ: + default: 0 + description: + long: If set, the mission feasibility checker will check for a takeoff waypoint on the mission. + short: Take-off waypoint required + type: boolean + volatile: false + MIS_YAW_ERR: + decimal: 1 + default: 12.0 + description: + short: Max yaw error in degrees needed for waypoint heading acceptance + increment: 1 + max: 90 + min: 0 + type: float + unit: deg + volatile: false + MIS_YAW_TMT: + decimal: 1 + default: -1.0 + description: + long: If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default. + short: Time we wait on reaching target heading at a waypoint if forced + increment: 1 + max: 20 + min: -1 + type: float + unit: s + volatile: false + group: Mission + - definitions: + NAV_AH_ALT: + decimal: 1 + default: 600.0 + description: + long: Altitude of airfield home waypoint + short: Airfield home alt + increment: 0.5 + min: -50 + type: float + unit: m + volatile: false + NAV_AH_LAT: + default: -265847810 + description: + long: Latitude of airfield home waypoint + short: Airfield home Lat + max: 900000000 + min: -900000000 + type: int32 + unit: deg*1e7 + volatile: false + NAV_AH_LON: + default: 1518423250 + description: + long: Longitude of airfield home waypoint + short: Airfield home Lon + max: 1800000000 + min: -1800000000 + type: int32 + unit: deg*1e7 + volatile: false + group: Data Link Loss + - definitions: + NAV_ACC_RAD: + decimal: 1 + default: 10.0 + description: + long: Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the L1 turning distance is used for horizontal acceptance. + short: Acceptance Radius + increment: 0.5 + max: 200.0 + min: 0.05 + type: float + unit: m + volatile: false + NAV_FORCE_VT: + default: 1 + description: + short: Force VTOL mode takeoff and land + type: boolean + volatile: false + NAV_FW_ALTL_RAD: + decimal: 1 + default: 5.0 + description: + long: Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required. + short: FW Altitude Acceptance Radius before a landing + max: 200.0 + min: 0.05 + type: float + unit: m + volatile: false + NAV_FW_ALT_RAD: + decimal: 1 + default: 10.0 + description: + long: Acceptance radius for fixedwing altitude. + short: FW Altitude Acceptance Radius + increment: 0.5 + max: 200.0 + min: 0.05 + type: float + unit: m + volatile: false + NAV_LOITER_RAD: + decimal: 1 + default: 80.0 + description: + long: Default value of loiter radius for missions, Hold mode, Return mode, etc. (fixedwing only). + short: Loiter radius (FW only) + increment: 0.5 + max: 1000 + min: 25 + type: float + unit: m + volatile: false + NAV_MC_ALT_RAD: + decimal: 1 + default: 0.8 + description: + long: Acceptance radius for multicopter altitude. + short: MC Altitude Acceptance Radius + increment: 0.5 + max: 200.0 + min: 0.05 + type: float + unit: m + volatile: false + NAV_TRAFF_AVOID: + default: 1 + description: + long: Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders + short: Set traffic avoidance mode + type: enum + values: + 0: Disabled + 1: Warn only + 2: Return mode + 3: Land mode + 4: Position Hold mode + volatile: false + NAV_TRAFF_A_RADM: + default: 500 + description: + long: Defines the Radius where NAV TRAFFIC AVOID is Called For Manned Aviation + short: Set NAV TRAFFIC AVOID RADIUS MANNED + min: 500 + type: float + unit: m + volatile: false + NAV_TRAFF_A_RADU: + default: 10 + description: + long: Defines the Radius where NAV TRAFFIC AVOID is Called For Unmanned Aviation + short: Set NAV TRAFFIC AVOID RADIUS + max: 500 + min: 10 + type: float + unit: m + volatile: false + group: Mission + - definitions: + PLD_BTOUT: + decimal: 1 + default: 5.0 + description: + long: Time after which the landing target is considered lost without any new measurements. + short: Landing Target Timeout + increment: 0.5 + max: 50 + min: 0.0 + type: float + unit: s + volatile: false + PLD_FAPPR_ALT: + decimal: 2 + default: 0.1 + description: + long: Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground. + short: Final approach altitude + increment: 0.1 + max: 10 + min: 0.0 + type: float + unit: m + volatile: false + PLD_HACC_RAD: + decimal: 2 + default: 0.2 + description: + long: Start descending if closer above landing target than this. + short: Horizontal acceptance radius + increment: 0.1 + max: 10 + min: 0.0 + type: float + unit: m + volatile: false + PLD_MAX_SRCH: + default: 3 + description: + long: Maximum number of times to search for the landing target if it is lost during the precision landing. + short: Maximum number of search attempts + max: 100 + min: 0 + type: int32 + volatile: false + PLD_SRCH_ALT: + decimal: 1 + default: 10.0 + description: + long: Altitude above home to which to climb when searching for the landing target. + short: Search altitude + increment: 0.1 + max: 100 + min: 0.0 + type: float + unit: m + volatile: false + PLD_SRCH_TOUT: + decimal: 1 + default: 10.0 + description: + long: Time allowed to search for the landing target before falling back to normal landing. + short: Search timeout + increment: 0.1 + max: 100 + min: 0.0 + type: float + unit: s + volatile: false + group: Precision Land + - definitions: + RTL_CONE_ANG: + default: 45 + description: + long: Defines the half-angle of a cone centered around the destination position that affects the altitude at which the vehicle returns. + short: Half-angle of the return mode altitude cone + max: 90 + min: 0 + type: enum + unit: deg + values: + 0: No cone, always climb to RTL_RETURN_ALT above destination. + 25: 25 degrees half cone angle. + 45: 45 degrees half cone angle. + 65: 65 degrees half cone angle. + 80: 80 degrees half cone angle. + 90: Only climb to at least RTL_DESCEND_ALT above destination. + volatile: false + RTL_DESCEND_ALT: + decimal: 1 + default: 30 + description: + long: Descend to this altitude (above destination position) after return, and wait for time defined in RTL_LAND_DELAY. Land (i.e. slowly descend) from this altitude if autolanding allowed. + short: Return mode loiter altitude + increment: 0.5 + max: 100 + min: 2 + type: float + unit: m + volatile: false + RTL_HDG_MD: + default: 0 + description: + long: Defines the heading behavior during RTL + short: RTL heading mode + type: enum + values: + 0: Towards next waypoint. + 1: Heading matches destination. + 2: Use current heading. + volatile: false + RTL_LAND_DELAY: + decimal: 1 + default: 0.0 + description: + long: Delay before landing (after initial descent) in Return mode. If set to -1 the system will not land but loiter at RTL_DESCEND_ALT. + short: Return mode delay + increment: 0.5 + max: 300 + min: -1 + type: float + unit: s + volatile: false + RTL_LOITER_RAD: + decimal: 1 + default: 80.0 + description: + long: Set the radius for loitering to a safe altitude for VTOL transition. + short: Loiter radius for rtl descend + increment: 0.5 + max: 1000 + min: 25 + type: float + unit: m + volatile: false + RTL_MIN_DIST: + decimal: 1 + default: 10.0 + description: + long: The return altitude will be calculated based on RTL_CONE_ANG parameter. The yaw setpoint will switch to the one defined by corresponding waypoint. + short: Horizontal radius within which special RTL rules apply + increment: 0.5 + max: 100 + min: 0.5 + type: float + unit: m + volatile: false + RTL_PLD_MD: + default: 0 + description: + long: Use precision landing when doing an RTL landing phase. + short: RTL precision land mode + type: enum + values: + 0: No precision landing + 1: Opportunistic precision landing + 2: Required precision landing + volatile: false + RTL_RETURN_ALT: + decimal: 1 + default: 60 + description: + long: Default minimum altitude above destination (e.g. home, safe point, landing pattern) for return flight. This is affected by RTL_MIN_DIST and RTL_CONE_ANG. + short: Return mode return altitude + increment: 0.5 + max: 150 + min: 0 + type: float + unit: m + volatile: false + RTL_TYPE: + default: 0 + description: + long: Return mode destination and flight path (home location, rally point, mission landing pattern, reverse mission) + short: Return type + type: enum + values: + 0: Return to closest safe point (home or rally point) via direct path. + 1: Return to closest safe point other than home (mission landing pattern or rally point), via direct path. If no mission landing or rally points are defined return home via direct path. Always chose closest safe landing point if vehicle is a VTOL in hover mode. + 2: Return to a planned mission landing, if available, using the mission path, else return to home via the reverse mission path. Do not consider rally points. + 3: 'Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land.' + volatile: false + group: Return Mode + - definitions: + RTL_TIME_FACTOR: + decimal: 1 + default: 1.1 + description: + long: Safety factor that is used to scale the actual RTL time estiamte. Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN + short: RTL time estimate safety margin factor + increment: 0.1 + max: 2.0 + min: 1.0 + type: float + volatile: false + RTL_TIME_MARGIN: + decimal: 1 + default: 100 + description: + long: Margin that is added to the time estimate, after it has already been scaled Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN + short: RTL time estimate safety margin offset + increment: 1 + max: 3600 + min: 0 + type: int32 + unit: s + volatile: false + group: Return To Land + - definitions: + VTO_LOITER_ALT: + decimal: 1 + default: 80 + description: + long: Altitude relative to home at which vehicle will loiter after front transition. + short: VTOL Takeoff relative loiter altitude + increment: 1 + max: 300 + min: 20 + type: float + unit: m + volatile: false + group: VTOL Takeoff diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c deleted file mode 100644 index e396faebe634..000000000000 --- a/src/modules/navigator/navigator_params.c +++ /dev/null @@ -1,200 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file navigator_params.c - * - * Parameters for navigator in general - * - * @author Julian Oes - * @author Thomas Gubler - */ - -/** - * Loiter radius (FW only) - * - * Default value of loiter radius for missions, Hold mode, Return mode, etc. (fixedwing only). - * - * @unit m - * @min 25 - * @max 1000 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 80.0f); - -/** - * Acceptance Radius - * - * Default acceptance radius, overridden by acceptance radius of waypoint if set. - * For fixed wing the L1 turning distance is used for horizontal acceptance. - * - * @unit m - * @min 0.05 - * @max 200.0 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 10.0f); - -/** - * FW Altitude Acceptance Radius - * - * Acceptance radius for fixedwing altitude. - * - * @unit m - * @min 0.05 - * @max 200.0 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_FW_ALT_RAD, 10.0f); - -/** - * FW Altitude Acceptance Radius before a landing - * - * Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller - * than the standard vertical acceptance because close to the ground higher accuracy is required. - * - * @unit m - * @min 0.05 - * @max 200.0 - * @decimal 1 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_FW_ALTL_RAD, 5.0f); - -/** - * MC Altitude Acceptance Radius - * - * Acceptance radius for multicopter altitude. - * - * @unit m - * @min 0.05 - * @max 200.0 - * @decimal 1 - * @increment 0.5 - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_MC_ALT_RAD, 0.8f); - -/** - * Set traffic avoidance mode - * - * Enabling this will allow the system to respond - * to transponder data from e.g. ADSB transponders - * - * @value 0 Disabled - * @value 1 Warn only - * @value 2 Return mode - * @value 3 Land mode - * @value 4 Position Hold mode - * - * @group Mission - */ -PARAM_DEFINE_INT32(NAV_TRAFF_AVOID, 1); - -/** - * Set NAV TRAFFIC AVOID RADIUS MANNED - * - * Defines the Radius where NAV TRAFFIC AVOID is Called - * For Manned Aviation - * - * @unit m - * @min 500 - * - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_TRAFF_A_RADM, 500); - -/** - * Set NAV TRAFFIC AVOID RADIUS - * - * Defines the Radius where NAV TRAFFIC AVOID is Called - * For Unmanned Aviation - * - * @unit m - * @min 10 - * @max 500 - * - * @group Mission - */ -PARAM_DEFINE_FLOAT(NAV_TRAFF_A_RADU, 10); - -/** - * Airfield home Lat - * - * Latitude of airfield home waypoint - * - * @unit deg*1e7 - * @min -900000000 - * @max 900000000 - * @group Data Link Loss - */ -PARAM_DEFINE_INT32(NAV_AH_LAT, -265847810); - -/** - * Airfield home Lon - * - * Longitude of airfield home waypoint - * - * @unit deg*1e7 - * @min -1800000000 - * @max 1800000000 - * @group Data Link Loss - */ -PARAM_DEFINE_INT32(NAV_AH_LON, 1518423250); - -/** - * Airfield home alt - * - * Altitude of airfield home waypoint - * - * @unit m - * @min -50 - * @decimal 1 - * @increment 0.5 - * @group Data Link Loss - */ -PARAM_DEFINE_FLOAT(NAV_AH_ALT, 600.0f); - -/** - * Force VTOL mode takeoff and land - * - * @boolean - * @group Mission - */ -PARAM_DEFINE_INT32(NAV_FORCE_VT, 1); diff --git a/src/modules/navigator/precland_params.c b/src/modules/navigator/precland_params.c deleted file mode 100644 index 9c2e63ac3258..000000000000 --- a/src/modules/navigator/precland_params.c +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file precland_params.c - * - * Parameters for precision landing. - * - * @author Nicolas de Palezieux (Sunflower Labs) - */ - -/** - * Landing Target Timeout - * - * Time after which the landing target is considered lost without any new measurements. - * - * @unit s - * @min 0.0 - * @max 50 - * @decimal 1 - * @increment 0.5 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_BTOUT, 5.0f); - -/** - * Horizontal acceptance radius - * - * Start descending if closer above landing target than this. - * - * @unit m - * @min 0.0 - * @max 10 - * @decimal 2 - * @increment 0.1 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_HACC_RAD, 0.2f); - -/** - * Final approach altitude - * - * Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground. - * - * @unit m - * @min 0.0 - * @max 10 - * @decimal 2 - * @increment 0.1 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_FAPPR_ALT, 0.1f); - -/** - * Search altitude - * - * Altitude above home to which to climb when searching for the landing target. - * - * @unit m - * @min 0.0 - * @max 100 - * @decimal 1 - * @increment 0.1 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_SRCH_ALT, 10.0f); - -/** - * Search timeout - * - * Time allowed to search for the landing target before falling back to normal landing. - * - * @unit s - * @min 0.0 - * @max 100 - * @decimal 1 - * @increment 0.1 - * @group Precision Land - */ -PARAM_DEFINE_FLOAT(PLD_SRCH_TOUT, 10.0f); - -/** - * Maximum number of search attempts - * - * Maximum number of times to search for the landing target if it is lost during the precision landing. - * - * @min 0 - * @max 100 - * @group Precision Land - */ -PARAM_DEFINE_INT32(PLD_MAX_SRCH, 3); diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c deleted file mode 100644 index 0e0376c1b566..000000000000 --- a/src/modules/navigator/rtl_params.c +++ /dev/null @@ -1,205 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file rtl_params.c - * - * Parameters for return mode - * - * @author Julian Oes - */ - -/* - * Return mode parameters, accessible via MAVLink - */ - -/** - * Return mode return altitude - * - * Default minimum altitude above destination (e.g. home, safe point, landing pattern) for return flight. - * This is affected by RTL_MIN_DIST and RTL_CONE_ANG. - * - * @unit m - * @min 0 - * @max 150 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 60); - - -/** - * Return mode loiter altitude - * - * Descend to this altitude (above destination position) after return, and wait for time defined in RTL_LAND_DELAY. - * Land (i.e. slowly descend) from this altitude if autolanding allowed. - * - * @unit m - * @min 2 - * @max 100 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 30); - -/** - * Return mode delay - * - * Delay before landing (after initial descent) in Return mode. - * If set to -1 the system will not land but loiter at RTL_DESCEND_ALT. - * - * @unit s - * @min -1 - * @max 300 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, 0.0f); - -/** - * Horizontal radius from return point within which special rules for return mode apply. - * - * The return altitude will be calculated based on RTL_CONE_ANG parameter. - * The yaw setpoint will switch to the one defined by corresponding waypoint. - * - * - * @unit m - * @min 0.5 - * @max 100 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_MIN_DIST, 10.0f); - -/** - * Return type - * - * Return mode destination and flight path (home location, rally point, mission landing pattern, reverse mission) - * - * @value 0 Return to closest safe point (home or rally point) via direct path. - * @value 1 Return to closest safe point other than home (mission landing pattern or rally point), via direct path. If no mission landing or rally points are defined return home via direct path. Always chose closest safe landing point if vehicle is a VTOL in hover mode. - * @value 2 Return to a planned mission landing, if available, using the mission path, else return to home via the reverse mission path. Do not consider rally points. - * @value 3 Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land. - * @group Return Mode - */ -PARAM_DEFINE_INT32(RTL_TYPE, 0); - -/** - * Half-angle of the return mode altitude cone - * - * Defines the half-angle of a cone centered around the destination position that - * affects the altitude at which the vehicle returns. - * - * @unit deg - * @min 0 - * @max 90 - * @value 0 No cone, always climb to RTL_RETURN_ALT above destination. - * @value 25 25 degrees half cone angle. - * @value 45 45 degrees half cone angle. - * @value 65 65 degrees half cone angle. - * @value 80 80 degrees half cone angle. - * @value 90 Only climb to at least RTL_DESCEND_ALT above destination. - * @group Return Mode - */ -PARAM_DEFINE_INT32(RTL_CONE_ANG, 45); - -/** - * RTL precision land mode - * - * Use precision landing when doing an RTL landing phase. - * - * @value 0 No precision landing - * @value 1 Opportunistic precision landing - * @value 2 Required precision landing - * @group Return Mode - */ -PARAM_DEFINE_INT32(RTL_PLD_MD, 0); - -/** - * Loiter radius for rtl descend - * - * Set the radius for loitering to a safe altitude for VTOL transition. - * - * @unit m - * @min 25 - * @max 1000 - * @decimal 1 - * @increment 0.5 - * @group Return Mode - */ -PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 80.0f); - -/** - * RTL heading mode - * - * Defines the heading behavior during RTL - * - * @value 0 Towards next waypoint. - * @value 1 Heading matches destination. - * @value 2 Use current heading. - * @group Return Mode - */ -PARAM_DEFINE_INT32(RTL_HDG_MD, 0); - -/** - * RTL time estimate safety margin factor - * - * Safety factor that is used to scale the actual RTL time estiamte. - * Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN - * - * @min 1.0 - * @max 2.0 - * @decimal 1 - * @increment 0.1 - * @group Return To Land - */ -PARAM_DEFINE_FLOAT(RTL_TIME_FACTOR, 1.1f); - -/** - * RTL time estimate safety margin offset - * - * Margin that is added to the time estimate, after it has already been scaled - * Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN - * - * @unit s - * @min 0 - * @max 3600 - * @decimal 1 - * @increment 1 - * @group Return To Land - */ -PARAM_DEFINE_INT32(RTL_TIME_MARGIN, 100); diff --git a/src/modules/navigator/vtol_takeoff_params.c b/src/modules/navigator/vtol_takeoff_params.c deleted file mode 100644 index 63379f1cf979..000000000000 --- a/src/modules/navigator/vtol_takeoff_params.c +++ /dev/null @@ -1,53 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file VTOLTakeoff_params.c - * - * Parameters for the VTOL takeoff navigation mode. - * - */ - -/** - * VTOL Takeoff relative loiter altitude. - * - * Altitude relative to home at which vehicle will loiter after front transition. - * - * @unit m - * @min 20 - * @max 300 - * @decimal 1 - * @increment 1 - * @group VTOL Takeoff - */ -PARAM_DEFINE_FLOAT(VTO_LOITER_ALT, 80); diff --git a/src/modules/rc_update/CMakeLists.txt b/src/modules/rc_update/CMakeLists.txt index 927e2f96f2b6..b00988aef73b 100644 --- a/src/modules/rc_update/CMakeLists.txt +++ b/src/modules/rc_update/CMakeLists.txt @@ -37,6 +37,8 @@ px4_add_module( SRCS rc_update.cpp rc_update.h + MODULE_CONFIG + module.yaml DEPENDS hysteresis mathlib diff --git a/src/modules/rc_update/module.yaml b/src/modules/rc_update/module.yaml new file mode 100644 index 000000000000..b90a033b068b --- /dev/null +++ b/src/modules/rc_update/module.yaml @@ -0,0 +1,1051 @@ +__max_number_rc_instances: &max_number_rc_instances 18 +module_name: rc_update +parameters: + - definitions: + RC${i}_DZ: + default: 10.0 + description: + long: The +- range of this value around the trim value will be considered as zero. + short: RC channel ${i} dead zone + max: 100.0 + min: 0.0 + type: float + unit: us + volatile: false + num_instances: *max_number_rc_instances + instance_start: 1 + RC${i}_MAX: + default: 2000 + description: + long: Maximum value for this channel. + short: RC channel ${i} maximum + max: 2200.0 + min: 1500.0 + type: float + unit: us + volatile: false + num_instances: *max_number_rc_instances + instance_start: 1 + RC${i}_MIN: + default: 1000 + description: + long: Minimum value for this channel. + short: RC channel ${i} minimum + max: 1500.0 + min: 800.0 + type: float + unit: us + volatile: false + num_instances: *max_number_rc_instances + instance_start: 1 + RC${i}_REV: + default: 1.0 + description: + long: Set to -1.0 to reverse channel, and 1.0 for normal direction. + short: RC channel ${i} reverse + max: 1.0 + min: -1.0 + type: float + volatile: false + num_instances: *max_number_rc_instances + instance_start: 1 + RC${i}_TRIM: + default: 1500 + description: + long: Mid point value (has to be set to the same as min for throttle channel). + short: RC channel ${i} trim + max: 2200.0 + min: 800.0 + type: float + unit: us + volatile: false + num_instances: *max_number_rc_instances + instance_start: 1 + RC_CHAN_CNT: + default: 0 + description: + long: This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use. + short: RC channel count + max: 18 + min: 0 + type: int32 + volatile: false + RC_FAILS_THR: + default: 0 + description: + long: 'Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this theshold. By default this is the throttle channel. Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, but below the minimum PWM value for the channel during normal operation. Note: The default value of 0 disables the feature (it is below the expected range).' + short: Failsafe channel PWM threshold + max: 2200 + min: 0 + type: int32 + unit: us + volatile: false + RC_MAP_AUX1: + default: 0 + description: + long: 'Default function: Camera pitch' + short: AUX1 Passthrough RC channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_AUX2: + default: 0 + description: + long: 'Default function: Camera roll' + short: AUX2 Passthrough RC channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_AUX3: + default: 0 + description: + long: 'Default function: Camera azimuth / yaw' + short: AUX3 Passthrough RC channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_AUX4: + default: 0 + description: + short: AUX4 Passthrough RC channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_AUX5: + default: 0 + description: + short: AUX5 Passthrough RC channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_AUX6: + default: 0 + description: + short: AUX6 Passthrough RC channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_FAILSAFE: + default: 0 + description: + long: Configures which RC channel is used by the receiver to indicate the signal was lost (on receivers that use output a fixed signal value to report lost signal). If set to 0, the channel mapped to throttle is used. Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence disabled. + short: Failsafe channel mapping + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_PARAM1: + default: 0 + description: + long: Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate * + short: PARAM1 tuning channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_PARAM2: + default: 0 + description: + long: Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate * + short: PARAM2 tuning channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_PARAM3: + default: 0 + description: + long: Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate * + short: PARAM3 tuning channel + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_PITCH: + default: 0 + description: + long: The channel index (starting from 1 for channel 1) indicates which channel should be used for reading pitch inputs from. A value of zero indicates the switch is not assigned. + short: Pitch control channel mapping + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_ROLL: + default: 0 + description: + long: The channel index (starting from 1 for channel 1) indicates which channel should be used for reading roll inputs from. A value of zero indicates the switch is not assigned. + short: Roll control channel mapping + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_THROTTLE: + default: 0 + description: + long: The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned. + short: Throttle control channel mapping + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_MAP_YAW: + default: 0 + description: + long: The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned. + short: Yaw control channel mapping + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_RSSI_PWM_CHAN: + default: 0 + description: + long: '0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.' + short: PWM input channel that provides RSSI + max: 18 + min: 0 + type: enum + values: + 0: Unassigned + 1: Channel 1 + 2: Channel 2 + 3: Channel 3 + 4: Channel 4 + 5: Channel 5 + 6: Channel 6 + 7: Channel 7 + 8: Channel 8 + 9: Channel 9 + 10: Channel 10 + 11: Channel 11 + 12: Channel 12 + 13: Channel 13 + 14: Channel 14 + 15: Channel 15 + 16: Channel 16 + 17: Channel 17 + 18: Channel 18 + volatile: false + RC_RSSI_PWM_MAX: + default: 2000 + description: + long: Only used if RC_RSSI_PWM_CHAN > 0 + short: Max input value for RSSI reading + max: 2000 + min: 0 + type: int32 + volatile: false + RC_RSSI_PWM_MIN: + default: 1000 + description: + long: Only used if RC_RSSI_PWM_CHAN > 0 + short: Min input value for RSSI reading + max: 2000 + min: 0 + type: int32 + volatile: false + group: Radio Calibration + - definitions: + RC_ARMSWITCH_TH: + default: 0.75 + description: + long: '0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth - * negative : true when channel
th - * negative : true when channelth - * negative : true when channelth - * negative : true when channelth - * negative : true when channelth - * negative : true when channelth - * negative : true when channel 0 - * - * @min 0 - * @max 2000 - * @group Radio Calibration - * - */ -PARAM_DEFINE_INT32(RC_RSSI_PWM_MIN, 1000); - -/** - * Max input value for RSSI reading. - * - * Only used if RC_RSSI_PWM_CHAN > 0 - * - * @min 0 - * @max 2000 - * @group Radio Calibration - * - */ -PARAM_DEFINE_INT32(RC_RSSI_PWM_MAX, 2000); diff --git a/src/modules/rc_update/params_deprecated.c b/src/modules/rc_update/params_deprecated.c deleted file mode 100644 index 93c06dd19c0b..000000000000 --- a/src/modules/rc_update/params_deprecated.c +++ /dev/null @@ -1,205 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Mode switch channel mapping (deprecated) - * - * This is the main flight mode selector. - * The channel index (starting from 1 for channel 1) indicates - * which channel should be used for deciding about the main mode. - * A value of zero indicates the switch is not assigned. - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0); - -/** - * Rattitude switch channel (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_RATT_SW, 0); - -/** - * Position Control switch channel (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0); - -/** - * Acro switch channel (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0); - -/** - * Stabilize switch channel mapping (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_STAB_SW, 0); - -/** - * Manual switch channel mapping (deprecated) - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_MAN_SW, 0); diff --git a/src/modules/rover_pos_control/CMakeLists.txt b/src/modules/rover_pos_control/CMakeLists.txt index 5e093862e768..1206b0b25444 100644 --- a/src/modules/rover_pos_control/CMakeLists.txt +++ b/src/modules/rover_pos_control/CMakeLists.txt @@ -36,6 +36,8 @@ px4_add_module( SRCS RoverPositionControl.cpp RoverPositionControl.hpp + MODULE_CONFIG + module.yaml DEPENDS l1 pid diff --git a/src/modules/rover_pos_control/module.yaml b/src/modules/rover_pos_control/module.yaml new file mode 100644 index 000000000000..a2d115b69418 --- /dev/null +++ b/src/modules/rover_pos_control/module.yaml @@ -0,0 +1,202 @@ +module_name: rover_pos_control +parameters: + - definitions: + GND_L1_DAMPING: + decimal: 2 + default: 0.75 + description: + long: Damping factor for L1 control. + short: L1 damping + increment: 0.05 + max: 0.9 + min: 0.6 + type: float + volatile: false + GND_L1_DIST: + decimal: 1 + default: 1.0 + description: + long: This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy). + short: L1 distance + increment: 0.1 + max: 50.0 + min: 1.0 + type: float + unit: m + volatile: false + GND_L1_PERIOD: + decimal: 1 + default: 5.0 + description: + long: 'This is the L1 distance and defines the tracking point ahead of the rover it''s following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation.' + short: L1 period + increment: 0.5 + max: 50.0 + min: 0.5 + type: float + unit: m + volatile: false + GND_MAN_Y_MAX: + decimal: 1 + default: 150.0 + description: + short: Max manual yaw rate + max: 400 + min: 0.0 + type: float + unit: deg/s + volatile: false + GND_MAX_ANG: + decimal: 3 + default: 0.7854 + description: + long: At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians. + short: Maximum turn angle for Ackerman steering + increment: 0.01 + max: 3.14159 + min: 0.0 + type: float + unit: rad + volatile: false + GND_SPEED_D: + decimal: 3 + default: 0.001 + description: + long: This is the derivative gain for the speed closed loop controller + short: Speed proportional gain + increment: 0.005 + max: 50.0 + min: 0.0 + type: float + unit: '%m/s' + volatile: false + GND_SPEED_I: + decimal: 3 + default: 3.0 + description: + long: This is the integral gain for the speed closed loop controller + short: Speed Integral gain + increment: 0.005 + max: 50.0 + min: 0.0 + type: float + unit: '%m/s' + volatile: false + GND_SPEED_IMAX: + decimal: 3 + default: 1.0 + description: + long: This is the maxim value the integral can reach to prevent wind-up. + short: Speed integral maximum value + increment: 0.005 + max: 50.0 + min: 0.005 + type: float + unit: '%m/s' + volatile: false + GND_SPEED_MAX: + decimal: 1 + default: 10.0 + description: + short: Maximum ground speed + increment: 0.5 + max: 40 + min: 0.0 + type: float + unit: m/s + volatile: false + GND_SPEED_P: + decimal: 3 + default: 2.0 + description: + long: This is the proportional gain for the speed closed loop controller + short: Speed proportional gain + increment: 0.005 + max: 50.0 + min: 0.005 + type: float + unit: '%m/s' + volatile: false + GND_SPEED_THR_SC: + decimal: 3 + default: 1.0 + description: + long: This is a gain to map the speed control output to the throttle linearly. + short: Speed to throttle scaler + increment: 0.005 + max: 50.0 + min: 0.005 + type: float + unit: '%m/s' + volatile: false + GND_SPEED_TRIM: + decimal: 1 + default: 3.0 + description: + short: Trim ground speed + increment: 0.5 + max: 40 + min: 0.0 + type: float + unit: m/s + volatile: false + GND_SP_CTRL_MODE: + default: 1 + description: + long: This allows the user to choose between closed loop gps speed or open loop cruise throttle speed + short: Control mode for speed + max: 1 + min: 0 + type: enum + values: + 0: open loop control + 1: close the loop with gps speed + volatile: false + GND_THR_CRUISE: + decimal: 2 + default: 0.1 + description: + long: This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode + short: Cruise throttle + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + GND_THR_MAX: + decimal: 2 + default: 0.3 + description: + long: This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough + short: Throttle limit max + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + GND_THR_MIN: + decimal: 2 + default: 0.0 + description: + long: This is the minimum throttle % that can be used by the controller. Set to 0 for rover + short: Throttle limit min + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + unit: norm + volatile: false + GND_WHEEL_BASE: + decimal: 3 + default: 0.31 + description: + long: A value of 0.31 is typical for 1/10 RC cars. + short: Distance from front axle to rear axle + increment: 0.01 + min: 0.0 + type: float + unit: m + volatile: false + group: Rover Position Control diff --git a/src/modules/rover_pos_control/rover_pos_control_params.c b/src/modules/rover_pos_control/rover_pos_control_params.c deleted file mode 100644 index 6458fb1fea65..000000000000 --- a/src/modules/rover_pos_control/rover_pos_control_params.c +++ /dev/null @@ -1,287 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file rover_pos_control_params.c - * - * Parameters defined by the position control task for ground rovers - * - * This is a modification of the fixed wing params and it is designed for ground rovers. - * It has been developed starting from the fw module, simplified and improved with dedicated items. - * - * All the ackowledgments and credits for the fw wing app are reported in those files. - * - * @author Marco Zorzi - */ - -/* - * Controller parameters, accessible via MAVLink - */ - -/** - * Distance from front axle to rear axle - * - * A value of 0.31 is typical for 1/10 RC cars. - * - * @unit m - * @min 0.0 - * @decimal 3 - * @increment 0.01 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_WHEEL_BASE, 0.31f); - -/** - * L1 distance - * - * This is the distance at which the next waypoint is activated. This should be set - * to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy). - * - * - * @unit m - * @min 1.0 - * @max 50.0 - * @decimal 1 - * @increment 0.1 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_L1_DIST, 1.0f); - -/** - * L1 period - * - * This is the L1 distance and defines the tracking - * point ahead of the rover it's following. - * Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten - * slowly during tuning until response is sharp without oscillation. - * - * @unit m - * @min 0.5 - * @max 50.0 - * @decimal 1 - * @increment 0.5 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_L1_PERIOD, 5.0f); - -/** - * L1 damping - * - * Damping factor for L1 control. - * - * @min 0.6 - * @max 0.9 - * @decimal 2 - * @increment 0.05 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_L1_DAMPING, 0.75f); - -/** - * Cruise throttle - * - * This is the throttle setting required to achieve the desired cruise speed. - * 10% is ok for a traxxas stampede vxl with ESC set to training mode - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_THR_CRUISE, 0.1f); - -/** - * Throttle limit max - * - * This is the maximum throttle % that can be used by the controller. - * For a Traxxas stampede vxl with the ESC set to training, 30 % is enough - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_THR_MAX, 0.3f); - -/** - * Throttle limit min - * - * This is the minimum throttle % that can be used by the controller. - * Set to 0 for rover - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_THR_MIN, 0.0f); - -/** - * Control mode for speed - * - * This allows the user to choose between closed loop gps speed or open loop cruise throttle speed - * @min 0 - * @max 1 - * @value 0 open loop control - * @value 1 close the loop with gps speed - * @group Rover Position Control - */ -PARAM_DEFINE_INT32(GND_SP_CTRL_MODE, 1); - -/** - * Speed proportional gain - * - * This is the proportional gain for the speed closed loop controller - * - * @unit %m/s - * @min 0.005 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_SPEED_P, 2.0f); - -/** - * Speed Integral gain - * - * This is the integral gain for the speed closed loop controller - * - * @unit %m/s - * @min 0.00 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_SPEED_I, 3.0f); - -/** - * Speed proportional gain - * - * This is the derivative gain for the speed closed loop controller - * - * @unit %m/s - * @min 0.00 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_SPEED_D, 0.001f); - -/** - * Speed integral maximum value - * - * This is the maxim value the integral can reach to prevent wind-up. - * - * @unit %m/s - * @min 0.005 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_SPEED_IMAX, 1.0f); - -/** - * Speed to throttle scaler - * - * This is a gain to map the speed control output to the throttle linearly. - * - * @unit %m/s - * @min 0.005 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_SPEED_THR_SC, 1.0f); - -/** - * Trim ground speed - * - * - * @unit m/s - * @min 0.0 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_SPEED_TRIM, 3.0f); - -/** - * Maximum ground speed - * - * - * @unit m/s - * @min 0.0 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_SPEED_MAX, 10.0f); - -/** - * Maximum turn angle for Ackerman steering. - * - * At a control output of 0, the steering wheels are at 0 radians. - * At a control output of 1, the steering wheels are at GND_MAX_ANG radians. - * - * @unit rad - * @min 0.0 - * @max 3.14159 - * @decimal 3 - * @increment 0.01 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_MAX_ANG, 0.7854f); - -/** - * Max manual yaw rate - * - * @unit deg/s - * @min 0.0 - * @max 400 - * @decimal 1 - * @group Rover Position Control - */ -PARAM_DEFINE_FLOAT(GND_MAN_Y_MAX, 150.0f); diff --git a/src/modules/sensors/module.yaml b/src/modules/sensors/module.yaml index d64b87de9300..798f97c2d526 100644 --- a/src/modules/sensors/module.yaml +++ b/src/modules/sensors/module.yaml @@ -1,547 +1,1018 @@ __max_num_sensor_instances: &max_num_sensor_instances 4 - module_name: sensors - parameters: - - group: Sensor Calibration - definitions: - - # Accelerometer calibration - CAL_ACC${i}_ID: - description: - short: Accelerometer ${i} calibration device ID - long: Device ID of the accelerometer this calibration applies to. - category: System - type: int32 - default: 0 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_ACC${i}_PRIO: - description: - short: Accelerometer ${i} priority - category: System - type: enum - values: - -1: Uninitialized - 0: Disabled - 1: Min - 25: Low - 50: Medium (Default) - 75: High - 100: Max - default: -1 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_ACC${i}_ROT: - description: - short: Accelerometer ${i} rotation relative to airframe - long: | - 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. - category: System - type: enum - values: - -1: Internal - 0: No rotation - 1: Yaw 45° - 2: Yaw 90° - 3: Yaw 135° - 4: Yaw 180° - 5: Yaw 225° - 6: Yaw 270° - 7: Yaw 315° - 8: Roll 180° - 9: Roll 180°, Yaw 45° - 10: Roll 180°, Yaw 90° - 11: Roll 180°, Yaw 135° - 12: Pitch 180° - 13: Roll 180°, Yaw 225° - 14: Roll 180°, Yaw 270° - 15: Roll 180°, Yaw 315° - 16: Roll 90° - 17: Roll 90°, Yaw 45° - 18: Roll 90°, Yaw 90° - 19: Roll 90°, Yaw 135° - 20: Roll 270° - 21: Roll 270°, Yaw 45° - 22: Roll 270°, Yaw 90° - 23: Roll 270°, Yaw 135° - 24: Pitch 90° - 25: Pitch 270° - 26: Pitch 180°, Yaw 90° - 27: Pitch 180°, Yaw 270° - 28: Roll 90°, Pitch 90° - 29: Roll 180°, Pitch 90° - 30: Roll 270°, Pitch 90° - 31: Roll 90°, Pitch 180° - 32: Roll 270°, Pitch 180° - 33: Roll 90°, Pitch 270° - 34: Roll 180°, Pitch 270° - 35: Roll 270°, Pitch 270° - 36: Roll 90°, Pitch 180°, Yaw 90° - 37: Roll 90°, Yaw 270° - 38: Roll 90°, Pitch 68°, Yaw 293° - 39: Pitch 315° - 40: Roll 90°, Pitch 315° - min: -1 - max: 40 - default: -1 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_ACC${i}_XOFF: - description: - short: Accelerometer ${i} X-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_ACC${i}_YOFF: - description: - short: Accelerometer ${i} Y-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_ACC${i}_ZOFF: - description: - short: Accelerometer ${i} Z-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_ACC${i}_XSCALE: - description: - short: Accelerometer ${i} X-axis scaling factor - category: System - type: float - default: 1.0 - min: 0.1 - max: 3.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_ACC${i}_YSCALE: - description: - short: Accelerometer ${i} Y-axis scaling factor - category: System - type: float - default: 1.0 - min: 0.1 - max: 3.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_ACC${i}_ZSCALE: - description: - short: Accelerometer ${i} Z-axis scaling factor - category: System - type: float - default: 1.0 - min: 0.1 - max: 3.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - # Barometer calibration - CAL_BARO${i}_ID: - description: - short: Barometer ${i} calibration device ID - long: Device ID of the barometer this calibration applies to. - category: System - type: int32 - default: 0 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_BARO${i}_PRIO: - description: - short: Barometer ${i} priority - category: System - type: enum - values: - -1: Uninitialized - 0: Disabled - 1: Min - 25: Low - 50: Medium (Default) - 75: High - 100: Max - default: -1 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_BARO${i}_OFF: - description: - short: Barometer ${i} offset - category: System - type: float - default: 0.0 - #unit: Pa - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - # Gyroscope calibration - CAL_GYRO${i}_ID: - description: - short: Gyroscope ${i} calibration device ID - long: Device ID of the gyroscope this calibration applies to. - category: System - type: int32 - default: 0 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_GYRO${i}_PRIO: - description: - short: Gyroscope ${i} priority - category: System - type: enum - values: - -1: Uninitialized - 0: Disabled - 1: Min - 25: Low - 50: Medium (Default) - 75: High - 100: Max - default: -1 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_GYRO${i}_ROT: - description: - short: Gyroscope ${i} rotation relative to airframe - long: | - 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. - category: System - type: enum - values: - -1: Internal - 0: No rotation - 1: Yaw 45° - 2: Yaw 90° - 3: Yaw 135° - 4: Yaw 180° - 5: Yaw 225° - 6: Yaw 270° - 7: Yaw 315° - 8: Roll 180° - 9: Roll 180°, Yaw 45° - 10: Roll 180°, Yaw 90° - 11: Roll 180°, Yaw 135° - 12: Pitch 180° - 13: Roll 180°, Yaw 225° - 14: Roll 180°, Yaw 270° - 15: Roll 180°, Yaw 315° - 16: Roll 90° - 17: Roll 90°, Yaw 45° - 18: Roll 90°, Yaw 90° - 19: Roll 90°, Yaw 135° - 20: Roll 270° - 21: Roll 270°, Yaw 45° - 22: Roll 270°, Yaw 90° - 23: Roll 270°, Yaw 135° - 24: Pitch 90° - 25: Pitch 270° - 26: Pitch 180°, Yaw 90° - 27: Pitch 180°, Yaw 270° - 28: Roll 90°, Pitch 90° - 29: Roll 180°, Pitch 90° - 30: Roll 270°, Pitch 90° - 31: Roll 90°, Pitch 180° - 32: Roll 270°, Pitch 180° - 33: Roll 90°, Pitch 270° - 34: Roll 180°, Pitch 270° - 35: Roll 270°, Pitch 270° - 36: Roll 90°, Pitch 180°, Yaw 90° - 37: Roll 90°, Yaw 270° - 38: Roll 90°, Pitch 68°, Yaw 293° - 39: Pitch 315° - 40: Roll 90°, Pitch 315° - min: -1 - max: 40 - default: -1 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_GYRO${i}_XOFF: - description: - short: Gyroscope ${i} X-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_GYRO${i}_YOFF: - description: - short: Gyroscope ${i} Y-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_GYRO${i}_ZOFF: - description: - short: Gyroscope ${i} Z-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - # Magnetometer calibration - CAL_MAG${i}_ID: - description: - short: Magnetometer ${i} calibration device ID - long: Device ID of the magnetometer this calibration applies to. - category: System - type: int32 - default: 0 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_PRIO: - description: - short: Magnetometer ${i} priority - category: System - type: enum - values: - -1: Uninitialized - 0: Disabled - 1: Min - 25: Low - 50: Medium (Default) - 75: High - 100: Max - default: -1 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_ROT: - description: - short: Magnetometer ${i} rotation relative to airframe - long: | - 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. - category: System - type: enum - values: - -1: Internal - 0: No rotation - 1: Yaw 45° - 2: Yaw 90° - 3: Yaw 135° - 4: Yaw 180° - 5: Yaw 225° - 6: Yaw 270° - 7: Yaw 315° - 8: Roll 180° - 9: Roll 180°, Yaw 45° - 10: Roll 180°, Yaw 90° - 11: Roll 180°, Yaw 135° - 12: Pitch 180° - 13: Roll 180°, Yaw 225° - 14: Roll 180°, Yaw 270° - 15: Roll 180°, Yaw 315° - 16: Roll 90° - 17: Roll 90°, Yaw 45° - 18: Roll 90°, Yaw 90° - 19: Roll 90°, Yaw 135° - 20: Roll 270° - 21: Roll 270°, Yaw 45° - 22: Roll 270°, Yaw 90° - 23: Roll 270°, Yaw 135° - 24: Pitch 90° - 25: Pitch 270° - 26: Pitch 180°, Yaw 90° - 27: Pitch 180°, Yaw 270° - 28: Roll 90°, Pitch 90° - 29: Roll 180°, Pitch 90° - 30: Roll 270°, Pitch 90° - 31: Roll 90°, Pitch 180° - 32: Roll 270°, Pitch 180° - 33: Roll 90°, Pitch 270° - 34: Roll 180°, Pitch 270° - 35: Roll 270°, Pitch 270° - 36: Roll 90°, Pitch 180°, Yaw 90° - 37: Roll 90°, Yaw 270° - 38: Roll 90°, Pitch 68°, Yaw 293° - 39: Pitch 315° - 40: Roll 90°, Pitch 315° - min: -1 - max: 40 - default: -1 - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_XOFF: - description: - short: Magnetometer ${i} X-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_YOFF: - description: - short: Magnetometer ${i} Y-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_ZOFF: - description: - short: Magnetometer ${i} Z-axis offset - category: System - type: float - default: 0.0 - unit: m - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_XSCALE: - description: - short: Magnetometer ${i} X-axis scaling factor - category: System - type: float - default: 1.0 - min: 0.1 - max: 3.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_YSCALE: - description: - short: Magnetometer ${i} Y-axis scaling factor - category: System - type: float - default: 1.0 - min: 0.1 - max: 3.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_ZSCALE: - description: - short: Magnetometer ${i} Z-axis scaling factor - category: System - type: float - default: 1.0 - min: 0.1 - max: 3.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_XODIAG: - description: - short: Magnetometer ${i} X-axis off diagonal scale factor - category: System - type: float - default: 0.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_YODIAG: - description: - short: Magnetometer ${i} Y-axis off diagonal scale factor - category: System - type: float - default: 0.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_ZODIAG: - description: - short: Magnetometer ${i} Z-axis off diagonal scale factor - category: System - type: float - default: 0.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_XCOMP: - description: - short: Magnetometer ${i} X Axis throttle compensation - long: | - 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] - category: System - type: float - default: 0.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_YCOMP: - description: - short: Magnetometer ${i} Y Axis throttle compensation - long: | - 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] - category: System - type: float - default: 0.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 - - CAL_MAG${i}_ZCOMP: - description: - short: Magnetometer ${i} Z Axis throttle compensation - long: | - 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] - category: System - type: float - default: 0.0 - volatile: true - num_instances: *max_num_sensor_instances - instance_start: 0 + - definitions: + SENS_BARO_QNH: + default: 1013.25 + description: + short: QNH for barometer + max: 1500 + min: 500 + type: float + unit: hPa + volatile: false + SENS_BARO_RATE: + default: 20.0 + description: + long: Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependant on the sensor. + short: Baro max rate + max: 200 + min: 1 + type: float + unit: Hz + volatile: false + group: Sensors + - definitions: + SENS_GPS_MASK: + bit: + 0: use speed accuracy + 1: use hpos accuracy + 2: use vpos accuracy + default: 7 + description: + long: 'Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy' + short: Multi GPS Blending Control Mask + max: 7 + min: 0 + type: bitmask + volatile: false + SENS_GPS_PRIME: + default: 0 + description: + long: When no blending is active, this defines the preferred GPS receiver instance. The GPS selection logic waits until the primary receiver is available to send data to the EKF even if a secondary instance is already available. The secondary instance is then only used if the primary one times out. To have an equal priority of all the instances, set this parameter to -1 and the best receiver will be used. This parameter has no effect if blending is active. + short: Multi GPS primary instance + max: 1 + min: -1 + type: int32 + volatile: false + SENS_GPS_TAU: + decimal: 1 + default: 10.0 + description: + long: Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences. + short: Multi GPS Blending Time Constant + max: 100.0 + min: 1.0 + type: float + unit: s + volatile: false + group: Sensors + - definitions: + IMU_ACCEL_CUTOFF: + default: 30.0 + description: + long: The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter. + short: Low pass filter cutoff frequency for accel + max: 1000 + min: 0 + reboot_required: true + type: float + unit: Hz + volatile: false + group: Sensors + - definitions: + IMU_DGYRO_CUTOFF: + default: 30.0 + description: + long: The cutoff frequency for the 2nd order butterworth filter used on the time derivative of the measured angular velocity, also known as the D-term filter in the rate controller. The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to increase IMU_GYRO_CUTOFF, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter. + short: Cutoff frequency for angular acceleration (D-Term filter) + max: 1000 + min: 0 + reboot_required: true + type: float + unit: Hz + volatile: false + IMU_GYRO_CUTOFF: + default: 40.0 + description: + long: The cutoff frequency for the 2nd order butterworth filter on the primary gyro. This only affects the angular velocity sent to the controllers, not the estimators. It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF. A value of 0 disables the filter. + short: Low pass filter cutoff frequency for gyro + max: 1000 + min: 0 + reboot_required: true + type: float + unit: Hz + volatile: false + IMU_GYRO_DNF_BW: + default: 15.0 + description: + long: Bandwidth per notch filter when using dynamic notch filtering with ESC RPM. + short: IMU gyro ESC notch filter bandwidth + max: 30 + min: 5 + type: float + volatile: false + IMU_GYRO_DNF_EN: + bit: + 0: ESC RPM + 1: FFT + default: 0 + description: + long: Enable bank of dynamically updating notch filters. Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN). + short: IMU gyro dynamic notch filtering + max: 3 + min: 0 + type: bitmask + volatile: false + IMU_GYRO_DNF_HMC: + default: 3 + description: + long: ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering. + short: IMU gyro dynamic notch filter harmonics + max: 7 + min: 1 + type: int32 + volatile: false + IMU_GYRO_NF0_BW: + default: 20.0 + description: + long: The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF0_FRQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. + short: Notch filter bandwidth for gyro + max: 100 + min: 0 + reboot_required: true + type: float + unit: Hz + volatile: false + IMU_GYRO_NF0_FRQ: + default: 0.0 + description: + long: The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF0_BW" to set the bandwidth of the filter. A value of 0 disables the filter. + short: Notch filter frequency for gyro + max: 1000 + min: 0 + reboot_required: true + type: float + unit: Hz + volatile: false + IMU_GYRO_NF1_BW: + default: 20.0 + description: + long: The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF1_FRQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. + short: Notch filter 1 bandwidth for gyro + max: 100 + min: 0 + reboot_required: true + type: float + unit: Hz + volatile: false + IMU_GYRO_NF1_FRQ: + default: 0.0 + description: + long: The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF1_BW" to set the bandwidth of the filter. A value of 0 disables the filter. + short: Notch filter 2 frequency for gyro + max: 1000 + min: 0 + reboot_required: true + type: float + unit: Hz + volatile: false + IMU_GYRO_RATEMAX: + default: 400 + description: + long: 'The maximum rate the gyro control data (vehicle_angular_velocity) will be allowed to publish at. This is the loop rate for the rate controller and outputs. Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.' + short: Gyro control data maximum publication rate (inner loop rate) + max: 2000 + min: 100 + reboot_required: true + type: enum + unit: Hz + values: + 100: 100 Hz + 250: 250 Hz + 400: 400 Hz + 800: 800 Hz + 1000: 1000 Hz + 2000: 2000 Hz + volatile: false + group: Sensors + - definitions: + IMU_INTEG_RATE: + default: 200 + description: + long: The rate at which raw IMU data is integrated to produce delta angles and delta velocities. Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2). + short: IMU integration rate + max: 1000 + min: 100 + reboot_required: true + type: enum + unit: Hz + values: + 100: 100 Hz + 200: 200 Hz + 250: 250 Hz + 400: 400 Hz + volatile: false + SENS_IMU_AUTOCAL: + category: System + default: 1 + description: + long: Automatically initialize IMU (accel/gyro) calibration from bias estimates if available. + short: IMU auto calibration + type: boolean + volatile: false + group: Sensors + - definitions: + SENS_DPRES_ANSC: + default: 0 + description: + long: 'Pick the appropriate scaling from the datasheet. this number defines the (linear) conversion from voltage to Pascal (pa). For the MPXV7002DP this is 1000. NOTE: If the sensor always registers zero, try switching the static and dynamic tubes.' + short: Differential pressure sensor analog scaling + type: float + volatile: false + SENS_DPRES_OFF: + category: System + default: 0.0 + description: + long: The offset (zero-reading) in Pascal + short: Differential pressure sensor offset + type: float + volatile: true + group: Sensor Calibration + - definitions: + CAL_AIR_CMODEL: + default: 0 + description: + long: 'Model with Pitot CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Model without Pitot (1.5 mm tubes) CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Tube Pressure Drop CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.' + short: Airspeed sensor compensation model for the SDP3x + type: enum + values: + 0: Model with Pitot + 1: Model without Pitot (1.5 mm tubes) + 2: Tube Pressure Drop + volatile: false + CAL_AIR_TUBED_MM: + default: 1.5 + description: + short: Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation + max: 100 + min: 1.5 + type: float + unit: mm + volatile: false + CAL_AIR_TUBELEN: + default: 0.2 + description: + long: See the CAL_AIR_CMODEL explanation on how this parameter should be set. + short: Airspeed sensor tube length + max: 2.0 + min: 0.01 + type: float + unit: m + volatile: false + SENS_BOARD_ROT: + default: 0 + description: + long: This parameter defines the rotation of the FMU board relative to the platform. + short: Board rotation + max: 40 + min: -1 + reboot_required: true + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + 8: "Roll 180°" + 9: "Roll 180°, Yaw 45°" + 10: "Roll 180°, Yaw 90°" + 11: "Roll 180°, Yaw 135°" + 12: "Pitch 180°" + 13: "Roll 180°, Yaw 225°" + 14: "Roll 180°, Yaw 270°" + 15: "Roll 180°, Yaw 315°" + 16: "Roll 90°" + 17: "Roll 90°, Yaw 45°" + 18: "Roll 90°, Yaw 90°" + 19: "Roll 90°, Yaw 135°" + 20: "Roll 270°" + 21: "Roll 270°, Yaw 45°" + 22: "Roll 270°, Yaw 90°" + 23: "Roll 270°, Yaw 135°" + 24: "Pitch 90°" + 25: "Pitch 270°" + 26: "Pitch 180°, Yaw 90°" + 27: "Pitch 180°, Yaw 270°" + 28: "Roll 90°, Pitch 90°" + 29: "Roll 180°, Pitch 90°" + 30: "Roll 270°, Pitch 90°" + 31: "Roll 90°, Pitch 180°" + 32: "Roll 270°, Pitch 180°" + 33: "Roll 90°, Pitch 270°" + 34: "Roll 180°, Pitch 270°" + 35: "Roll 270°, Pitch 270°" + 36: "Roll 90°, Pitch 180°, Yaw 90°" + 37: "Roll 90°, Yaw 270°" + 38: "Roll 90°, Pitch 68°, Yaw 293°" + 39: "Pitch 315°" + 40: "Roll 90°, Pitch 315°" + volatile: false + SENS_BOARD_X_OFF: + default: 0.0 + description: + long: This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user to fine tune the board offset in the event of misalignment. + short: Board rotation X (Roll) offset + type: float + unit: deg + volatile: false + SENS_BOARD_Y_OFF: + default: 0.0 + description: + long: This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user to fine tune the board offset in the event of misalignment. + short: Board rotation Y (Pitch) offset + type: float + unit: deg + volatile: false + SENS_BOARD_Z_OFF: + default: 0.0 + description: + long: This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment. + short: Board rotation Z (YAW) offset + type: float + unit: deg + volatile: false + SENS_EN_THERMAL: + category: System + default: -1 + description: + short: Thermal control of sensor temperature + type: enum + values: + -1: Thermal control unavailable + 0: Thermal control off + 1: Thermal control enabled + volatile: false + SENS_EXT_I2C_PRB: + category: System + default: 1 + description: + long: Probe for optional external I2C devices. + short: External I2C probe + type: boolean + volatile: false + SENS_IMU_MODE: + category: System + default: 1 + description: + short: Sensors hub IMU mode + reboot_required: true + type: enum + values: + 0: Disabled + 1: Publish primary IMU selection + volatile: false + SENS_INT_BARO_EN: + category: System + default: 1 + description: + long: For systems with an external barometer, this should be set to false to make sure that the external is used. + short: Enable internal barometers + reboot_required: true + type: boolean + volatile: false + group: Sensors + - definitions: + SENS_FLOW_MAXHGT: + decimal: 1 + default: 100.0 + description: + long: This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade. + short: Maximum height above ground when reliant on optical flow + increment: 0.1 + max: 100.0 + min: 1.0 + type: float + unit: m + volatile: false + SENS_FLOW_MAXR: + decimal: 2 + default: 8.0 + description: + long: Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of this value. + short: Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor + min: 1.0 + type: float + unit: rad/s + volatile: false + SENS_FLOW_MINHGT: + decimal: 1 + default: 0.08 + description: + long: This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. + short: Minimum height above ground when reliant on optical flow + increment: 0.1 + max: 1.0 + min: 0.0 + type: float + unit: m + volatile: false + group: Sensor Calibration + - definitions: + SENS_FLOW_RATE: + default: 70.0 + description: + long: Optical flow data maximum publication rate. This is an upper bound, actual optical flow data rate is still dependant on the sensor. + short: Optical flow max rate + max: 200 + min: 1 + reboot_required: true + type: float + unit: Hz + volatile: false + SENS_FLOW_ROT: + default: 0 + description: + long: This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. + short: Optical flow rotation + type: enum + values: + 0: No rotation + 1: "Yaw 45°" + 2: "Yaw 90°" + 3: "Yaw 135°" + 4: "Yaw 180°" + 5: "Yaw 225°" + 6: "Yaw 270°" + 7: "Yaw 315°" + volatile: false + group: Sensors + - definitions: + CAL_MAG_COMP_TYP: + category: System + default: 0 + description: + short: Type of magnetometer compensation + type: enum + values: + 0: Disabled + 1: Throttle-based compensation + 2: Current-based compensation (battery_status instance 0) + 3: Current-based compensation (battery_status instance 1) + volatile: false + group: Sensor Calibration + - definitions: + CAL_MAG_ROT_AUTO: + default: 1 + description: + long: During calibration attempt to automatically determine the rotation of external magnetometers. + short: Automatically set external rotations + type: boolean + volatile: false + CAL_MAG_SIDES: + default: 63 + description: + long: 'If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32' + short: Bitfield selecting mag sides for calibration + max: 63 + min: 34 + type: enum + values: + 34: Two side calibration + 38: Three side calibration + 63: Six side calibration + volatile: false + SENS_MAG_AUTOCAL: + category: System + default: 1 + description: + long: Automatically initialize magnetometer calibration from bias estimate if available. + short: Magnetometer auto calibration + type: boolean + volatile: false + SENS_MAG_MODE: + category: System + default: 1 + description: + short: Sensors hub mag mode + reboot_required: true + type: enum + values: + 0: Publish all magnetometers + 1: Publish primary magnetometer + volatile: false + SENS_MAG_RATE: + default: 15.0 + description: + long: Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependant on the sensor. + short: Magnetometer max rate + max: 200 + min: 1 + reboot_required: true + type: float + unit: Hz + volatile: false + group: Sensors + - group: Sensor Calibration + definitions: + # Accelerometer calibration + CAL_ACC${i}_ID: + description: + short: Accelerometer ${i} calibration device ID + long: Device ID of the accelerometer this calibration applies to. + category: System + type: int32 + default: 0 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_ACC${i}_PRIO: + description: + short: Accelerometer ${i} priority + category: System + type: enum + values: + -1: Uninitialized + 0: Disabled + 1: Min + 25: Low + 50: Medium (Default) + 75: High + 100: Max + default: -1 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_ACC${i}_ROT: + description: + short: Accelerometer ${i} rotation relative to airframe + long: | + 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. + category: System + type: enum + values: + -1: Internal + 0: No rotation + 1: Yaw 45° + 2: Yaw 90° + 3: Yaw 135° + 4: Yaw 180° + 5: Yaw 225° + 6: Yaw 270° + 7: Yaw 315° + 8: Roll 180° + 9: Roll 180°, Yaw 45° + 10: Roll 180°, Yaw 90° + 11: Roll 180°, Yaw 135° + 12: Pitch 180° + 13: Roll 180°, Yaw 225° + 14: Roll 180°, Yaw 270° + 15: Roll 180°, Yaw 315° + 16: Roll 90° + 17: Roll 90°, Yaw 45° + 18: Roll 90°, Yaw 90° + 19: Roll 90°, Yaw 135° + 20: Roll 270° + 21: Roll 270°, Yaw 45° + 22: Roll 270°, Yaw 90° + 23: Roll 270°, Yaw 135° + 24: Pitch 90° + 25: Pitch 270° + 26: Pitch 180°, Yaw 90° + 27: Pitch 180°, Yaw 270° + 28: Roll 90°, Pitch 90° + 29: Roll 180°, Pitch 90° + 30: Roll 270°, Pitch 90° + 31: Roll 90°, Pitch 180° + 32: Roll 270°, Pitch 180° + 33: Roll 90°, Pitch 270° + 34: Roll 180°, Pitch 270° + 35: Roll 270°, Pitch 270° + 36: Roll 90°, Pitch 180°, Yaw 90° + 37: Roll 90°, Yaw 270° + 38: Roll 90°, Pitch 68°, Yaw 293° + 39: Pitch 315° + 40: Roll 90°, Pitch 315° + min: -1 + max: 40 + default: -1 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_ACC${i}_XOFF: + description: + short: Accelerometer ${i} X-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_ACC${i}_YOFF: + description: + short: Accelerometer ${i} Y-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_ACC${i}_ZOFF: + description: + short: Accelerometer ${i} Z-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_ACC${i}_XSCALE: + description: + short: Accelerometer ${i} X-axis scaling factor + category: System + type: float + default: 1.0 + min: 0.1 + max: 3.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_ACC${i}_YSCALE: + description: + short: Accelerometer ${i} Y-axis scaling factor + category: System + type: float + default: 1.0 + min: 0.1 + max: 3.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_ACC${i}_ZSCALE: + description: + short: Accelerometer ${i} Z-axis scaling factor + category: System + type: float + default: 1.0 + min: 0.1 + max: 3.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + # Barometer calibration + CAL_BARO${i}_ID: + description: + short: Barometer ${i} calibration device ID + long: Device ID of the barometer this calibration applies to. + category: System + type: int32 + default: 0 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_BARO${i}_PRIO: + description: + short: Barometer ${i} priority + category: System + type: enum + values: + -1: Uninitialized + 0: Disabled + 1: Min + 25: Low + 50: Medium (Default) + 75: High + 100: Max + default: -1 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_BARO${i}_OFF: + description: + short: Barometer ${i} offset + category: System + type: float + default: 0.0 + #unit: Pa + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + # Gyroscope calibration + CAL_GYRO${i}_ID: + description: + short: Gyroscope ${i} calibration device ID + long: Device ID of the gyroscope this calibration applies to. + category: System + type: int32 + default: 0 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_GYRO${i}_PRIO: + description: + short: Gyroscope ${i} priority + category: System + type: enum + values: + -1: Uninitialized + 0: Disabled + 1: Min + 25: Low + 50: Medium (Default) + 75: High + 100: Max + default: -1 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_GYRO${i}_ROT: + description: + short: Gyroscope ${i} rotation relative to airframe + long: | + 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. + category: System + type: enum + values: + -1: Internal + 0: No rotation + 1: Yaw 45° + 2: Yaw 90° + 3: Yaw 135° + 4: Yaw 180° + 5: Yaw 225° + 6: Yaw 270° + 7: Yaw 315° + 8: Roll 180° + 9: Roll 180°, Yaw 45° + 10: Roll 180°, Yaw 90° + 11: Roll 180°, Yaw 135° + 12: Pitch 180° + 13: Roll 180°, Yaw 225° + 14: Roll 180°, Yaw 270° + 15: Roll 180°, Yaw 315° + 16: Roll 90° + 17: Roll 90°, Yaw 45° + 18: Roll 90°, Yaw 90° + 19: Roll 90°, Yaw 135° + 20: Roll 270° + 21: Roll 270°, Yaw 45° + 22: Roll 270°, Yaw 90° + 23: Roll 270°, Yaw 135° + 24: Pitch 90° + 25: Pitch 270° + 26: Pitch 180°, Yaw 90° + 27: Pitch 180°, Yaw 270° + 28: Roll 90°, Pitch 90° + 29: Roll 180°, Pitch 90° + 30: Roll 270°, Pitch 90° + 31: Roll 90°, Pitch 180° + 32: Roll 270°, Pitch 180° + 33: Roll 90°, Pitch 270° + 34: Roll 180°, Pitch 270° + 35: Roll 270°, Pitch 270° + 36: Roll 90°, Pitch 180°, Yaw 90° + 37: Roll 90°, Yaw 270° + 38: Roll 90°, Pitch 68°, Yaw 293° + 39: Pitch 315° + 40: Roll 90°, Pitch 315° + min: -1 + max: 40 + default: -1 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_GYRO${i}_XOFF: + description: + short: Gyroscope ${i} X-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_GYRO${i}_YOFF: + description: + short: Gyroscope ${i} Y-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_GYRO${i}_ZOFF: + description: + short: Gyroscope ${i} Z-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + # Magnetometer calibration + CAL_MAG${i}_ID: + description: + short: Magnetometer ${i} calibration device ID + long: Device ID of the magnetometer this calibration applies to. + category: System + type: int32 + default: 0 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_PRIO: + description: + short: Magnetometer ${i} priority + category: System + type: enum + values: + -1: Uninitialized + 0: Disabled + 1: Min + 25: Low + 50: Medium (Default) + 75: High + 100: Max + default: -1 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_ROT: + description: + short: Magnetometer ${i} rotation relative to airframe + long: | + 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. + category: System + type: enum + values: + -1: Internal + 0: No rotation + 1: Yaw 45° + 2: Yaw 90° + 3: Yaw 135° + 4: Yaw 180° + 5: Yaw 225° + 6: Yaw 270° + 7: Yaw 315° + 8: Roll 180° + 9: Roll 180°, Yaw 45° + 10: Roll 180°, Yaw 90° + 11: Roll 180°, Yaw 135° + 12: Pitch 180° + 13: Roll 180°, Yaw 225° + 14: Roll 180°, Yaw 270° + 15: Roll 180°, Yaw 315° + 16: Roll 90° + 17: Roll 90°, Yaw 45° + 18: Roll 90°, Yaw 90° + 19: Roll 90°, Yaw 135° + 20: Roll 270° + 21: Roll 270°, Yaw 45° + 22: Roll 270°, Yaw 90° + 23: Roll 270°, Yaw 135° + 24: Pitch 90° + 25: Pitch 270° + 26: Pitch 180°, Yaw 90° + 27: Pitch 180°, Yaw 270° + 28: Roll 90°, Pitch 90° + 29: Roll 180°, Pitch 90° + 30: Roll 270°, Pitch 90° + 31: Roll 90°, Pitch 180° + 32: Roll 270°, Pitch 180° + 33: Roll 90°, Pitch 270° + 34: Roll 180°, Pitch 270° + 35: Roll 270°, Pitch 270° + 36: Roll 90°, Pitch 180°, Yaw 90° + 37: Roll 90°, Yaw 270° + 38: Roll 90°, Pitch 68°, Yaw 293° + 39: Pitch 315° + 40: Roll 90°, Pitch 315° + min: -1 + max: 40 + default: -1 + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_XOFF: + description: + short: Magnetometer ${i} X-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_YOFF: + description: + short: Magnetometer ${i} Y-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_ZOFF: + description: + short: Magnetometer ${i} Z-axis offset + category: System + type: float + default: 0.0 + unit: m + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_XSCALE: + description: + short: Magnetometer ${i} X-axis scaling factor + category: System + type: float + default: 1.0 + min: 0.1 + max: 3.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_YSCALE: + description: + short: Magnetometer ${i} Y-axis scaling factor + category: System + type: float + default: 1.0 + min: 0.1 + max: 3.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_ZSCALE: + description: + short: Magnetometer ${i} Z-axis scaling factor + category: System + type: float + default: 1.0 + min: 0.1 + max: 3.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_XODIAG: + description: + short: Magnetometer ${i} X-axis off diagonal scale factor + category: System + type: float + default: 0.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_YODIAG: + description: + short: Magnetometer ${i} Y-axis off diagonal scale factor + category: System + type: float + default: 0.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_ZODIAG: + description: + short: Magnetometer ${i} Z-axis off diagonal scale factor + category: System + type: float + default: 0.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_XCOMP: + description: + short: Magnetometer ${i} X Axis throttle compensation + long: | + 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] + category: System + type: float + default: 0.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_YCOMP: + description: + short: Magnetometer ${i} Y Axis throttle compensation + long: | + 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] + category: System + type: float + default: 0.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 + CAL_MAG${i}_ZCOMP: + description: + short: Magnetometer ${i} Z Axis throttle compensation + long: | + 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] + category: System + type: float + default: 0.0 + volatile: true + num_instances: *max_num_sensor_instances + instance_start: 0 diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c deleted file mode 100644 index fd93e18dff7a..000000000000 --- a/src/modules/sensors/sensor_params.c +++ /dev/null @@ -1,235 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2019 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Airspeed sensor compensation model for the SDP3x - * - * Model with Pitot - * CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. - * CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. - * Model without Pitot (1.5 mm tubes) - * CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. - * CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. - * Tube Pressure Drop - * CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. - * CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot. - * - * @value 0 Model with Pitot - * @value 1 Model without Pitot (1.5 mm tubes) - * @value 2 Tube Pressure Drop - * - * @group Sensors - */ -PARAM_DEFINE_INT32(CAL_AIR_CMODEL, 0); - -/** - * Airspeed sensor tube length. - * - * See the CAL_AIR_CMODEL explanation on how this parameter should be set. - * - * @min 0.01 - * @max 2.00 - * @unit m - * - * @group Sensors - */ -PARAM_DEFINE_FLOAT(CAL_AIR_TUBELEN, 0.2f); - -/** - * Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation. - * - * @min 1.5 - * @max 100 - * @unit mm - * - * @group Sensors - */ -PARAM_DEFINE_FLOAT(CAL_AIR_TUBED_MM, 1.5f); - -/** - * Differential pressure sensor offset - * - * The offset (zero-reading) in Pascal - * - * @category system - * @group Sensor Calibration - * @volatile - */ -PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f); - -/** - * Differential pressure sensor analog scaling - * - * Pick the appropriate scaling from the datasheet. - * this number defines the (linear) conversion from voltage - * to Pascal (pa). For the MPXV7002DP this is 1000. - * - * NOTE: If the sensor always registers zero, try switching - * the static and dynamic tubes. - * - * @group Sensor Calibration - */ -PARAM_DEFINE_FLOAT(SENS_DPRES_ANSC, 0); - -/** - * Board rotation - * - * This parameter defines the rotation of the FMU board relative to the platform. - * - * @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° - * - * @min -1 - * @max 40 - * @reboot_required true - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0); - -/** - * Board rotation Y (Pitch) offset - * - * This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user - * to fine tune the board offset in the event of misalignment. - * - * @unit deg - * @group Sensors - */ -PARAM_DEFINE_FLOAT(SENS_BOARD_Y_OFF, 0.0f); - -/** - * Board rotation X (Roll) offset - * - * This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user - * to fine tune the board offset in the event of misalignment. - * - * @unit deg - * @group Sensors - */ -PARAM_DEFINE_FLOAT(SENS_BOARD_X_OFF, 0.0f); - -/** - * Board rotation Z (YAW) offset - * - * This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user - * to fine tune the board offset in the event of misalignment. - * - * @unit deg - * @group Sensors - */ -PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f); - -/** - * Thermal control of sensor temperature - * - * @value -1 Thermal control unavailable - * @value 0 Thermal control off - * @value 1 Thermal control enabled - * @category system - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EN_THERMAL, -1); - -/** - * External I2C probe. - * - * Probe for optional external I2C devices. - * - * @boolean - * @category system - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_EXT_I2C_PRB, 1); - -/** - * Sensors hub IMU mode - * - * @value 0 Disabled - * @value 1 Publish primary IMU selection - * - * @category system - * @reboot_required true - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_IMU_MODE, 1); - -/** - * Enable internal barometers - * - * For systems with an external barometer, this should be set to false to make sure that the external is used. - * - * @boolean - * @reboot_required true - * @category system - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_INT_BARO_EN, 1); diff --git a/src/modules/sensors/sensor_params_flow.c b/src/modules/sensors/sensor_params_flow.c deleted file mode 100644 index 7d3de7ff7a85..000000000000 --- a/src/modules/sensors/sensor_params_flow.c +++ /dev/null @@ -1,113 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Optical flow rotation - * - * This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. - * Zero rotation is defined as X on flow board pointing towards front of vehicle. - * - * @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° - * - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_FLOW_ROT, 0); - -/** - * Minimum height above ground when reliant on optical flow. - * - * This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. - * The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. - * - * @unit m - * @min 0.0 - * @max 1.0 - * @increment 0.1 - * @decimal 1 - * @group Sensor Calibration - */ -PARAM_DEFINE_FLOAT(SENS_FLOW_MINHGT, 0.08f); - -/** - * Maximum height above ground when reliant on optical flow. - * - * This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. - * The height setpoint will be limited to be no greater than this value when the navigation system - * is completely reliant on optical flow data and the height above ground estimate is valid. - * The sensor may be usable above this height, but accuracy will progressively degrade. - * - * @unit m - * @min 1.0 - * @max 100.0 - * @increment 0.1 - * @decimal 1 - * @group Sensor Calibration - */ -PARAM_DEFINE_FLOAT(SENS_FLOW_MAXHGT, 100.f); - -/** - * Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor. - * - * Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and - * control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground - * is less than 50% of this value. - * - * @unit rad/s - * @min 1.0 - * @decimal 2 - * @group Sensor Calibration - */ -PARAM_DEFINE_FLOAT(SENS_FLOW_MAXR, 8.f); - -/** - * Optical flow max rate. - * - * Optical flow data maximum publication rate. This is an upper bound, - * actual optical flow data rate is still dependant on the sensor. - * - * @min 1 - * @max 200 - * @group Sensors - * @unit Hz - * - * @reboot_required true - * - */ -PARAM_DEFINE_FLOAT(SENS_FLOW_RATE, 70.0f); diff --git a/src/modules/sensors/sensor_params_mag.c b/src/modules/sensors/sensor_params_mag.c deleted file mode 100644 index 6a904137ac1b..000000000000 --- a/src/modules/sensors/sensor_params_mag.c +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Bitfield selecting mag sides for calibration - * - * If set to two side calibration, only the offsets are estimated, the scale - * calibration is left unchanged. Thus an initial six side calibration is - * recommended. - * - * Bits: - * ORIENTATION_TAIL_DOWN = 1 - * ORIENTATION_NOSE_DOWN = 2 - * ORIENTATION_LEFT = 4 - * ORIENTATION_RIGHT = 8 - * ORIENTATION_UPSIDE_DOWN = 16 - * ORIENTATION_RIGHTSIDE_UP = 32 - * - * @min 34 - * @max 63 - * @value 34 Two side calibration - * @value 38 Three side calibration - * @value 63 Six side calibration - * @group Sensors - */ -PARAM_DEFINE_INT32(CAL_MAG_SIDES, 63); - -/** - * Type of magnetometer compensation - * - * @value 0 Disabled - * @value 1 Throttle-based compensation - * @value 2 Current-based compensation (battery_status instance 0) - * @value 3 Current-based compensation (battery_status instance 1) - * - * @category system - * @group Sensor Calibration - */ -PARAM_DEFINE_INT32(CAL_MAG_COMP_TYP, 0); - -/** - * Automatically set external rotations. - * - * During calibration attempt to automatically determine the rotation of external magnetometers. - * - * @boolean - * @group Sensors - */ -PARAM_DEFINE_INT32(CAL_MAG_ROT_AUTO, 1); - -/** - * Magnetometer max rate. - * - * Magnetometer data maximum publication rate. This is an upper bound, - * actual magnetometer data rate is still dependant on the sensor. - * - * @min 1 - * @max 200 - * @group Sensors - * @unit Hz - * - * @reboot_required true - * - */ -PARAM_DEFINE_FLOAT(SENS_MAG_RATE, 15.0f); - -/** - * Sensors hub mag mode - * - * @value 0 Publish all magnetometers - * @value 1 Publish primary magnetometer - * - * @category system - * @reboot_required true - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_MAG_MODE, 1); - -/** - * Magnetometer auto calibration - * - * Automatically initialize magnetometer calibration from bias estimate if available. - * - * @boolean - * - * @category system - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_MAG_AUTOCAL, 1); diff --git a/src/modules/sensors/vehicle_acceleration/imu_accel_parameters.c b/src/modules/sensors/vehicle_acceleration/imu_accel_parameters.c deleted file mode 100644 index c4fda14b94e5..000000000000 --- a/src/modules/sensors/vehicle_acceleration/imu_accel_parameters.c +++ /dev/null @@ -1,46 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* Low pass filter cutoff frequency for accel -* -* The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer. -* This only affects the signal sent to the controllers, not the estimators. 0 disables the filter. -* -* @min 0 -* @max 1000 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_ACCEL_CUTOFF, 30.0f); diff --git a/src/modules/sensors/vehicle_air_data/params.c b/src/modules/sensors/vehicle_air_data/params.c deleted file mode 100644 index 950529bbf91c..000000000000 --- a/src/modules/sensors/vehicle_air_data/params.c +++ /dev/null @@ -1,55 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * QNH for barometer - * - * @min 500 - * @max 1500 - * @group Sensors - * @unit hPa - */ -PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f); - -/** - * Baro max rate. - * - * Barometric air data maximum publication rate. This is an upper bound, - * actual barometric data rate is still dependant on the sensor. - * - * @min 1 - * @max 200 - * @group Sensors - * @unit Hz - */ -PARAM_DEFINE_FLOAT(SENS_BARO_RATE, 20.0f); diff --git a/src/modules/sensors/vehicle_angular_velocity/imu_gyro_parameters.c b/src/modules/sensors/vehicle_angular_velocity/imu_gyro_parameters.c deleted file mode 100644 index 8564503d5467..000000000000 --- a/src/modules/sensors/vehicle_angular_velocity/imu_gyro_parameters.c +++ /dev/null @@ -1,195 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* Notch filter frequency for gyro -* -* The center frequency for the 2nd order notch filter on the primary gyro. -* This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. -* This only affects the signal sent to the controllers, not the estimators. -* Applies to both angular velocity and angular acceleration sent to the controllers. -* See "IMU_GYRO_NF0_BW" to set the bandwidth of the filter. -* -* A value of 0 disables the filter. -* -* @min 0 -* @max 1000 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_NF0_FRQ, 0.0f); - -/** -* Notch filter bandwidth for gyro -* -* The frequency width of the stop band for the 2nd order notch filter on the primary gyro. -* See "IMU_GYRO_NF0_FRQ" to activate the filter and to set the notch frequency. -* Applies to both angular velocity and angular acceleration sent to the controllers. -* -* @min 0 -* @max 100 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_NF0_BW, 20.0f); - -/** -* Notch filter 2 frequency for gyro -* -* The center frequency for the 2nd order notch filter on the primary gyro. -* This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. -* This only affects the signal sent to the controllers, not the estimators. -* Applies to both angular velocity and angular acceleration sent to the controllers. -* See "IMU_GYRO_NF1_BW" to set the bandwidth of the filter. -* -* A value of 0 disables the filter. -* -* @min 0 -* @max 1000 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_NF1_FRQ, 0.0f); - -/** -* Notch filter 1 bandwidth for gyro -* -* The frequency width of the stop band for the 2nd order notch filter on the primary gyro. -* See "IMU_GYRO_NF1_FRQ" to activate the filter and to set the notch frequency. -* Applies to both angular velocity and angular acceleration sent to the controllers. -* -* @min 0 -* @max 100 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_NF1_BW, 20.0f); - - -/** -* Low pass filter cutoff frequency for gyro -* -* The cutoff frequency for the 2nd order butterworth filter on the primary gyro. -* This only affects the angular velocity sent to the controllers, not the estimators. -* It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF. -* -* A value of 0 disables the filter. -* -* @min 0 -* @max 1000 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_CUTOFF, 40.0f); - -/** -* Gyro control data maximum publication rate (inner loop rate) -* -* The maximum rate the gyro control data (vehicle_angular_velocity) will be -* allowed to publish at. This is the loop rate for the rate controller and outputs. -* -* Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting. -* -* @min 100 -* @max 2000 -* @value 100 100 Hz -* @value 250 250 Hz -* @value 400 400 Hz -* @value 800 800 Hz -* @value 1000 1000 Hz -* @value 2000 2000 Hz -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_INT32(IMU_GYRO_RATEMAX, 400); - -/** -* Cutoff frequency for angular acceleration (D-Term filter) -* -* The cutoff frequency for the 2nd order butterworth filter used on -* the time derivative of the measured angular velocity, also known as -* the D-term filter in the rate controller. The D-term uses the derivative of -* the rate and thus is the most susceptible to noise. Therefore, using -* a D-term filter allows to increase IMU_GYRO_CUTOFF, which -* leads to reduced control latency and permits to increase the P gains. -* -* A value of 0 disables the filter. -* -* @min 0 -* @max 1000 -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_FLOAT(IMU_DGYRO_CUTOFF, 30.0f); - -/** -* IMU gyro dynamic notch filtering -* -* Enable bank of dynamically updating notch filters. -* Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN). -* @group Sensors -* @min 0 -* @max 3 -* @bit 0 ESC RPM -* @bit 1 FFT -*/ -PARAM_DEFINE_INT32(IMU_GYRO_DNF_EN, 0); - -/** -* IMU gyro ESC notch filter bandwidth -* -* Bandwidth per notch filter when using dynamic notch filtering with ESC RPM. -* -* @group Sensors -* @min 5 -* @max 30 -*/ -PARAM_DEFINE_FLOAT(IMU_GYRO_DNF_BW, 15.f); - -/** -* IMU gyro dynamic notch filter harmonics -* -* ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering. -* -* @group Sensors -* @min 1 -* @max 7 -*/ -PARAM_DEFINE_INT32(IMU_GYRO_DNF_HMC, 3); diff --git a/src/modules/sensors/vehicle_gps_position/params.c b/src/modules/sensors/vehicle_gps_position/params.c deleted file mode 100644 index 651e6e15fa5f..000000000000 --- a/src/modules/sensors/vehicle_gps_position/params.c +++ /dev/null @@ -1,82 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Multi GPS Blending Control Mask. - * - * Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. - * 0 : Set to true to use speed accuracy - * 1 : Set to true to use horizontal position accuracy - * 2 : Set to true to use vertical position accuracy - * - * @group Sensors - * @min 0 - * @max 7 - * @bit 0 use speed accuracy - * @bit 1 use hpos accuracy - * @bit 2 use vpos accuracy - */ -PARAM_DEFINE_INT32(SENS_GPS_MASK, 7); - -/** - * Multi GPS Blending Time Constant - * - * Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences. - * - * - * @group Sensors - * @min 1.0 - * @max 100.0 - * @unit s - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(SENS_GPS_TAU, 10.0f); - -/** - * Multi GPS primary instance - * - * When no blending is active, this defines the preferred GPS receiver instance. - * The GPS selection logic waits until the primary receiver is available to - * send data to the EKF even if a secondary instance is already available. - * The secondary instance is then only used if the primary one times out. - * - * To have an equal priority of all the instances, set this parameter to -1 and - * the best receiver will be used. - * - * This parameter has no effect if blending is active. - * - * @group Sensors - * @min -1 - * @max 1 - */ -PARAM_DEFINE_INT32(SENS_GPS_PRIME, 0); diff --git a/src/modules/sensors/vehicle_imu/imu_parameters.c b/src/modules/sensors/vehicle_imu/imu_parameters.c deleted file mode 100644 index ebe8a465a672..000000000000 --- a/src/modules/sensors/vehicle_imu/imu_parameters.c +++ /dev/null @@ -1,62 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* IMU integration rate. -* -* The rate at which raw IMU data is integrated to produce delta angles and delta velocities. -* Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2). -* -* @min 100 -* @max 1000 -* @value 100 100 Hz -* @value 200 200 Hz -* @value 250 250 Hz -* @value 400 400 Hz -* @unit Hz -* @reboot_required true -* @group Sensors -*/ -PARAM_DEFINE_INT32(IMU_INTEG_RATE, 200); - -/** - * IMU auto calibration - * - * Automatically initialize IMU (accel/gyro) calibration from bias estimates if available. - * - * @boolean - * - * @category system - * @group Sensors - */ -PARAM_DEFINE_INT32(SENS_IMU_AUTOCAL, 1); diff --git a/src/modules/sih/CMakeLists.txt b/src/modules/sih/CMakeLists.txt index 02bd2d81d7af..39c8cf1d3c25 100644 --- a/src/modules/sih/CMakeLists.txt +++ b/src/modules/sih/CMakeLists.txt @@ -40,6 +40,8 @@ px4_add_module( aero.hpp sih.cpp sih.hpp + MODULE_CONFIG + module.yaml DEPENDS mathlib drivers_accelerometer diff --git a/src/modules/sih/module.yaml b/src/modules/sih/module.yaml new file mode 100644 index 000000000000..ffab26ec79b9 --- /dev/null +++ b/src/modules/sih/module.yaml @@ -0,0 +1,301 @@ +module_name: sih +parameters: + - definitions: + SIH_BARO_OFFSET: + default: 0.0 + description: + long: Absolute value superior to 10000 will disable barometer + short: Barometer offset in meters + type: float + unit: m + volatile: false + SIH_DISTSNSR_MAX: + decimal: 4 + default: 100.0 + description: + short: distance sensor maximun range + increment: 0.01 + max: 1000.0 + min: 0.0 + type: float + unit: m + volatile: false + SIH_DISTSNSR_MIN: + decimal: 4 + default: 0.0 + description: + short: distance sensor minimun range + increment: 0.01 + max: 10.0 + min: 0.0 + type: float + unit: m + volatile: false + SIH_DISTSNSR_OVR: + default: -1.0 + description: + long: Absolute value superior to 10000 will disable distance sensor + short: if >= 0 the distance sensor measures will be overrided by this value + type: float + unit: m + volatile: false + SIH_GPS_USED: + default: 10 + description: + short: Number of GPS satellites used + max: 50 + min: 0 + type: int32 + volatile: false + SIH_IXX: + decimal: 3 + default: 0.025 + description: + long: The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + short: Vehicle inertia about X axis + increment: 0.005 + min: 0.0 + type: float + unit: kg m^2 + volatile: false + SIH_IXY: + decimal: 3 + default: 0.0 + description: + long: The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + short: Vehicle cross term inertia xy + increment: 0.005 + type: float + unit: kg m^2 + volatile: false + SIH_IXZ: + decimal: 3 + default: 0.0 + description: + long: The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + short: Vehicle cross term inertia xz + increment: 0.005 + type: float + unit: kg m^2 + volatile: false + SIH_IYY: + decimal: 3 + default: 0.025 + description: + long: The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + short: Vehicle inertia about Y axis + increment: 0.005 + min: 0.0 + type: float + unit: kg m^2 + volatile: false + SIH_IYZ: + decimal: 3 + default: 0.0 + description: + long: The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + short: Vehicle cross term inertia yz + increment: 0.005 + type: float + unit: kg m^2 + volatile: false + SIH_IZZ: + decimal: 3 + default: 0.03 + description: + long: The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + short: Vehicle inertia about Z axis + increment: 0.005 + min: 0.0 + type: float + unit: kg m^2 + volatile: false + SIH_KDV: + decimal: 2 + default: 1.0 + description: + long: 'Physical coefficient representing the friction with air particules. The greater this value, the slower the quad will move. Drag force function of velocity: D=-KDV*V. The maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]' + short: First order drag coefficient + increment: 0.05 + min: 0.0 + type: float + unit: N/(m/s) + volatile: false + SIH_KDW: + decimal: 3 + default: 0.025 + description: + long: 'Physical coefficient representing the friction with air particules during rotations. The greater this value, the slower the quad will rotate. Aerodynamic moment function of body rate: Ma=-KDW*W_B. This value can be set to 0 if unknown.' + short: First order angular damper coefficient + increment: 0.005 + min: 0.0 + type: float + unit: Nm/(rad/s) + volatile: false + SIH_LOC_H0: + decimal: 2 + default: 32.34 + description: + long: This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. If using FlightGear as a visual animation, this value can be tweaked such that the vehicle lies on the ground at takeoff. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + short: Initial AMSL ground altitude + increment: 0.01 + max: 8848.0 + min: -420.0 + type: float + unit: m + volatile: false + SIH_LOC_LAT0: + default: 454671160 + description: + long: This value represents the North-South location on Earth where the simulation begins. A value of 45 deg should be written 450000000. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + short: Initial geodetic latitude + max: 850000000 + min: -850000000 + type: int32 + unit: deg*1e7 + volatile: false + SIH_LOC_LON0: + default: -737578370 + description: + long: This value represents the East-West location on Earth where the simulation begins. A value of 45 deg should be written 450000000. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + short: Initial geodetic longitude + max: 1800000000 + min: -1800000000 + type: int32 + unit: deg*1e7 + volatile: false + SIH_LOC_MU_X: + decimal: 2 + default: 0.179 + description: + long: This value represents the North magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + short: North magnetic field at the initial location + increment: 0.001 + max: 1.0 + min: -1.0 + type: float + unit: gauss + volatile: false + SIH_LOC_MU_Y: + decimal: 2 + default: -0.045 + description: + long: This value represents the East magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + short: East magnetic field at the initial location + increment: 0.001 + max: 1.0 + min: -1.0 + type: float + unit: gauss + volatile: false + SIH_LOC_MU_Z: + decimal: 2 + default: 0.504 + description: + long: This value represents the Down magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + short: Down magnetic field at the initial location + increment: 0.001 + max: 1.0 + min: -1.0 + type: float + unit: gauss + volatile: false + SIH_L_PITCH: + decimal: 2 + default: 0.2 + description: + long: This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors. + short: Pitch arm length + increment: 0.05 + min: 0.0 + type: float + unit: m + volatile: false + SIH_L_ROLL: + decimal: 2 + default: 0.2 + description: + long: This is the arm length generating the rolling moment This value can be measured with a ruler. This corresponds to half the distance between the left and right motors. + short: Roll arm length + increment: 0.05 + min: 0.0 + type: float + unit: m + volatile: false + SIH_MAG_OFFSET_X: + default: 0.0 + description: + long: Absolute value superior to 10000 will disable magnetometer + short: magnetometer X offset in Gauss + type: float + unit: gauss + volatile: false + SIH_MAG_OFFSET_Y: + default: 0.0 + description: + long: Absolute value superior to 10000 will disable magnetometer + short: magnetometer Y offset in Gauss + type: float + unit: gauss + volatile: false + SIH_MAG_OFFSET_Z: + default: 0.0 + description: + long: Absolute value superior to 10000 will disable magnetometer + short: magnetometer Z offset in Gauss + type: float + unit: gauss + volatile: false + SIH_MASS: + decimal: 2 + default: 1.0 + description: + long: This value can be measured by weighting the quad on a scale. + short: Vehicle mass + increment: 0.1 + min: 0.0 + type: float + unit: kg + volatile: false + SIH_Q_MAX: + decimal: 3 + default: 0.1 + description: + long: This is the maximum torque delivered by one propeller when the motor is running at full speed. This value is usually about few percent of the maximum thrust force. + short: Max propeller torque + increment: 0.05 + min: 0.0 + type: float + unit: Nm + volatile: false + SIH_T_MAX: + decimal: 2 + default: 5.0 + description: + long: This is the maximum force delivered by one propeller when the motor is running at full speed. This value is usually about 5 times the mass of the quadrotor. + short: Max propeller thrust force + increment: 0.5 + min: 0.0 + type: float + unit: N + volatile: false + SIH_T_TAU: + default: 0.05 + description: + long: the time taken for the thruster to step from 0 to 100% should be about 4 times tau + short: thruster time constant tau + type: float + unit: s + volatile: false + SIH_VEHICLE_TYPE: + default: 0 + description: + short: Vehicle type + reboot_required: true + type: enum + values: + 0: Multicopter + 1: Fixed-Wing + 2: Tailsitter + volatile: false + group: Simulation In Hardware diff --git a/src/modules/sih/sih_params.c b/src/modules/sih/sih_params.c deleted file mode 100644 index a174d78c3421..000000000000 --- a/src/modules/sih/sih_params.c +++ /dev/null @@ -1,448 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file sih_params.c - * Parameters for quadcopter X simulator in hardware. - * - * @author Romain Chiappinelli - * February 2019 - */ - -/** - * Vehicle mass - * - * This value can be measured by weighting the quad on a scale. - * - * @unit kg - * @min 0.0 - * @decimal 2 - * @increment 0.1 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_MASS, 1.0f); - -/** - * Vehicle inertia about X axis - * - * The intertia is a 3 by 3 symmetric matrix. - * It represents the difficulty of the vehicle to modify its angular rate. - * - * @unit kg m^2 - * @min 0.0 - * @decimal 3 - * @increment 0.005 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_IXX, 0.025f); - -/** - * Vehicle inertia about Y axis - * - * The intertia is a 3 by 3 symmetric matrix. - * It represents the difficulty of the vehicle to modify its angular rate. - * - * @unit kg m^2 - * @min 0.0 - * @decimal 3 - * @increment 0.005 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_IYY, 0.025f); - -/** - * Vehicle inertia about Z axis - * - * The intertia is a 3 by 3 symmetric matrix. - * It represents the difficulty of the vehicle to modify its angular rate. - * - * @unit kg m^2 - * @min 0.0 - * @decimal 3 - * @increment 0.005 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_IZZ, 0.030f); - -/** - * Vehicle cross term inertia xy - * - * The intertia is a 3 by 3 symmetric matrix. - * This value can be set to 0 for a quad symmetric about its center of mass. - * - * @unit kg m^2 - * @decimal 3 - * @increment 0.005 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_IXY, 0.0f); - -/** - * Vehicle cross term inertia xz - * - * The intertia is a 3 by 3 symmetric matrix. - * This value can be set to 0 for a quad symmetric about its center of mass. - * - * @unit kg m^2 - * @decimal 3 - * @increment 0.005 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_IXZ, 0.0f); - -/** - * Vehicle cross term inertia yz - * - * The intertia is a 3 by 3 symmetric matrix. - * This value can be set to 0 for a quad symmetric about its center of mass. - * - * @unit kg m^2 - * @decimal 3 - * @increment 0.005 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_IYZ, 0.0f); - -/** - * Max propeller thrust force - * - * This is the maximum force delivered by one propeller - * when the motor is running at full speed. - * - * This value is usually about 5 times the mass of the quadrotor. - * - * @unit N - * @min 0.0 - * @decimal 2 - * @increment 0.5 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_T_MAX, 5.0f); - -/** - * Max propeller torque - * - * This is the maximum torque delivered by one propeller - * when the motor is running at full speed. - * - * This value is usually about few percent of the maximum thrust force. - * - * @unit Nm - * @min 0.0 - * @decimal 3 - * @increment 0.05 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_Q_MAX, 0.1f); - -/** - * Roll arm length - * - * This is the arm length generating the rolling moment - * - * This value can be measured with a ruler. - * This corresponds to half the distance between the left and right motors. - * - * @unit m - * @min 0.0 - * @decimal 2 - * @increment 0.05 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_L_ROLL, 0.2f); - -/** - * Pitch arm length - * - * This is the arm length generating the pitching moment - * - * This value can be measured with a ruler. - * This corresponds to half the distance between the front and rear motors. - * - * @unit m - * @min 0.0 - * @decimal 2 - * @increment 0.05 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_L_PITCH, 0.2f); - -/** - * First order drag coefficient - * - * Physical coefficient representing the friction with air particules. - * The greater this value, the slower the quad will move. - * - * Drag force function of velocity: D=-KDV*V. - * The maximum freefall velocity can be computed as V=10*MASS/KDV [m/s] - * - * @unit N/(m/s) - * @min 0.0 - * @decimal 2 - * @increment 0.05 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_KDV, 1.0f); - -/** - * First order angular damper coefficient - * - * Physical coefficient representing the friction with air particules during rotations. - * The greater this value, the slower the quad will rotate. - * - * Aerodynamic moment function of body rate: Ma=-KDW*W_B. - * This value can be set to 0 if unknown. - * - * @unit Nm/(rad/s) - * @min 0.0 - * @decimal 3 - * @increment 0.005 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_KDW, 0.025f); - -/** - * Initial geodetic latitude - * - * This value represents the North-South location on Earth where the simulation begins. - * A value of 45 deg should be written 450000000. - * - * LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others - * to represent a physical ground location on Earth. - * - * @unit deg*1e7 - * @min -850000000 - * @max 850000000 - * @group Simulation In Hardware - */ -PARAM_DEFINE_INT32(SIH_LOC_LAT0, 454671160); - -/** - * Initial geodetic longitude - * - * This value represents the East-West location on Earth where the simulation begins. - * A value of 45 deg should be written 450000000. - * - * LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others - * to represent a physical ground location on Earth. - * - * @unit deg*1e7 - * @min -1800000000 - * @max 1800000000 - * @group Simulation In Hardware - */ -PARAM_DEFINE_INT32(SIH_LOC_LON0, -737578370); - -/** - * Initial AMSL ground altitude - * - * This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. - * - * If using FlightGear as a visual animation, - * this value can be tweaked such that the vehicle lies on the ground at takeoff. - * - * LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others - * to represent a physical ground location on Earth. - * - * - * @unit m - * @min -420.0 - * @max 8848.0 - * @decimal 2 - * @increment 0.01 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_LOC_H0, 32.34f); - -/** - * North magnetic field at the initial location - * - * This value represents the North magnetic field at the initial location. - * - * A magnetic field calculator can be found on the NOAA website - * Note, the values need to be converted from nano Tesla to Gauss - * - * LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others - * to represent a physical ground location on Earth. - * - * @unit gauss - * @min -1.0 - * @max 1.0 - * @decimal 2 - * @increment 0.001 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_LOC_MU_X, 0.179f); - -/** - * East magnetic field at the initial location - * - * This value represents the East magnetic field at the initial location. - * - * A magnetic field calculator can be found on the NOAA website - * Note, the values need to be converted from nano Tesla to Gauss - * - * LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others - * to represent a physical ground location on Earth. - * - * @unit gauss - * @min -1.0 - * @max 1.0 - * @decimal 2 - * @increment 0.001 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_LOC_MU_Y, -0.045f); - -/** - * Down magnetic field at the initial location - * - * This value represents the Down magnetic field at the initial location. - * - * A magnetic field calculator can be found on the NOAA website - * Note, the values need to be converted from nano Tesla to Gauss - * - * LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others - * to represent a physical ground location on Earth. - * - * @unit gauss - * @min -1.0 - * @max 1.0 - * @decimal 2 - * @increment 0.001 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_LOC_MU_Z, 0.504f); - -/** - * Number of GPS satellites used - * - * @min 0 - * @max 50 - * @group Simulation In Hardware - */ -PARAM_DEFINE_INT32(SIH_GPS_USED, 10); - -/** - * Barometer offset in meters - * - * Absolute value superior to 10000 will disable barometer - * - * @unit m - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_BARO_OFFSET, 0.0f); - -/** - * magnetometer X offset in Gauss - * - * Absolute value superior to 10000 will disable magnetometer - * - * @unit gauss - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_X, 0.0f); - -/** - * magnetometer Y offset in Gauss - * - * Absolute value superior to 10000 will disable magnetometer - * - * @unit gauss - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_Y, 0.0f); -/** - * magnetometer Z offset in Gauss - * - * Absolute value superior to 10000 will disable magnetometer - * - * @unit gauss - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_Z, 0.0f); - -/** - * distance sensor minimun range - * - * @unit m - * @min 0.0 - * @max 10.0 - * @decimal 4 - * @increment 0.01 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MIN, 0.0f); - -/** - * distance sensor maximun range - * - * @unit m - * @min 0.0 - * @max 1000.0 - * @decimal 4 - * @increment 0.01 - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MAX, 100.0f); - -/** - * if >= 0 the distance sensor measures will be overrided by this value - * - * Absolute value superior to 10000 will disable distance sensor - * - * @unit m - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_DISTSNSR_OVR, -1.0f); - -/** - * thruster time constant tau - * - * the time taken for the thruster to step from 0 to 100% should be about 4 times tau - * - * @unit s - * @group Simulation In Hardware - */ -PARAM_DEFINE_FLOAT(SIH_T_TAU, 0.05f); - -/** - * Vehicle type - * - * @value 0 Multicopter - * @value 1 Fixed-Wing - * @value 2 Tailsitter - * @reboot_required true - * @group Simulation In Hardware - */ -PARAM_DEFINE_INT32(SIH_VEHICLE_TYPE, 0); diff --git a/src/modules/simulator/battery_simulator/CMakeLists.txt b/src/modules/simulator/battery_simulator/CMakeLists.txt index c4ba81329e3f..8f493452f9d6 100644 --- a/src/modules/simulator/battery_simulator/CMakeLists.txt +++ b/src/modules/simulator/battery_simulator/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS BatterySimulator.cpp BatterySimulator.hpp + MODULE_CONFIG + module.yaml DEPENDS battery mathlib diff --git a/src/modules/simulator/battery_simulator/battery_simulator_params.c b/src/modules/simulator/battery_simulator/battery_simulator_params.c deleted file mode 100644 index d634714cf3c9..000000000000 --- a/src/modules/simulator/battery_simulator/battery_simulator_params.c +++ /dev/null @@ -1,59 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Simulator Battery drain interval - * - * @min 1 - * @max 86400 - * @increment 1 - * @unit s - * - * @group SITL - */ -PARAM_DEFINE_FLOAT(SIM_BAT_DRAIN, 60); - -/** - * Simulator Battery minimal percentage. - * - * Can be used to alter the battery level during SITL- or HITL-simulation on the fly. - * Particularly useful for testing different low-battery behaviour. - * - * @min 0 - * @max 100 - * @increment 0.1 - * @unit % - * - * @group SITL - */ -PARAM_DEFINE_FLOAT(SIM_BAT_MIN_PCT, 50.0f); diff --git a/src/modules/simulator/battery_simulator/module.yaml b/src/modules/simulator/battery_simulator/module.yaml new file mode 100644 index 000000000000..b79e055e2439 --- /dev/null +++ b/src/modules/simulator/battery_simulator/module.yaml @@ -0,0 +1,26 @@ +module_name: battery_simulator +parameters: +- definitions: + SIM_BAT_DRAIN: + default: 60 + description: + short: Simulator Battery drain interval + increment: 1 + max: 86400 + min: 1 + type: float + unit: s + volatile: false + SIM_BAT_MIN_PCT: + default: 50.0 + description: + long: Can be used to alter the battery level during SITL- or HITL-simulation + on the fly. Particularly useful for testing different low-battery behaviour. + short: Simulator Battery minimal percentage + increment: 0.1 + max: 100 + min: 0 + type: float + unit: '%' + volatile: false + group: SITL diff --git a/src/modules/simulator/sensor_baro_sim/CMakeLists.txt b/src/modules/simulator/sensor_baro_sim/CMakeLists.txt index d6571893019b..a16215a87faf 100644 --- a/src/modules/simulator/sensor_baro_sim/CMakeLists.txt +++ b/src/modules/simulator/sensor_baro_sim/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS SensorBaroSim.cpp SensorBaroSim.hpp + MODULE_CONFIG + module.yaml DEPENDS geo px4_work_queue diff --git a/src/modules/simulator/sensor_baro_sim/module.yaml b/src/modules/simulator/sensor_baro_sim/module.yaml new file mode 100644 index 000000000000..8da62b34f202 --- /dev/null +++ b/src/modules/simulator/sensor_baro_sim/module.yaml @@ -0,0 +1,17 @@ +module_name: sensor_baro_sim +parameters: +- definitions: + SIM_BARO_OFF_P: + default: 0.0 + description: + short: simulated barometer pressure offset + type: float + volatile: false + SIM_BARO_OFF_T: + default: 0.0 + description: + short: simulated barometer temperature offset + type: float + unit: celcius + volatile: false + group: Simulator diff --git a/src/modules/simulator/sensor_baro_sim/parameters.c b/src/modules/simulator/sensor_baro_sim/parameters.c deleted file mode 100644 index 8f0ea74a5f4c..000000000000 --- a/src/modules/simulator/sensor_baro_sim/parameters.c +++ /dev/null @@ -1,47 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * simulated barometer pressure offset - * - * @group Simulator - */ -PARAM_DEFINE_FLOAT(SIM_BARO_OFF_P, 0.0f); - -/** - * simulated barometer temperature offset - * - * @group Simulator - * @unit celcius - */ -PARAM_DEFINE_FLOAT(SIM_BARO_OFF_T, 0.0f); diff --git a/src/modules/simulator/sensor_gps_sim/CMakeLists.txt b/src/modules/simulator/sensor_gps_sim/CMakeLists.txt index 03af2f025a64..55b78df408b7 100644 --- a/src/modules/simulator/sensor_gps_sim/CMakeLists.txt +++ b/src/modules/simulator/sensor_gps_sim/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS SensorGpsSim.cpp SensorGpsSim.hpp + MODULE_CONFIG + module.yaml DEPENDS px4_work_queue ) diff --git a/src/modules/simulator/sensor_gps_sim/module.yaml b/src/modules/simulator/sensor_gps_sim/module.yaml new file mode 100644 index 000000000000..35ee87e4fa0c --- /dev/null +++ b/src/modules/simulator/sensor_gps_sim/module.yaml @@ -0,0 +1,12 @@ +module_name: sensor_gps_sim +parameters: +- definitions: + SIM_GPS_USED: + default: 10 + description: + short: simulated GPS number of satellites used + max: 50 + min: 0 + type: int32 + volatile: false + group: Simulator diff --git a/src/modules/simulator/sensor_gps_sim/parameters.c b/src/modules/simulator/sensor_gps_sim/parameters.c deleted file mode 100644 index 5d91834269e3..000000000000 --- a/src/modules/simulator/sensor_gps_sim/parameters.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * simulated GPS number of satellites used - * - * @min 0 - * @max 50 - * @group Simulator - */ -PARAM_DEFINE_INT32(SIM_GPS_USED, 10); diff --git a/src/modules/simulator/sensor_mag_sim/CMakeLists.txt b/src/modules/simulator/sensor_mag_sim/CMakeLists.txt index f22e9ffea941..b6aed9e640fb 100644 --- a/src/modules/simulator/sensor_mag_sim/CMakeLists.txt +++ b/src/modules/simulator/sensor_mag_sim/CMakeLists.txt @@ -38,6 +38,8 @@ px4_add_module( SRCS SensorMagSim.cpp SensorMagSim.hpp + MODULE_CONFIG + module.yaml DEPENDS drivers_magnetometer geo diff --git a/src/modules/simulator/sensor_mag_sim/module.yaml b/src/modules/simulator/sensor_mag_sim/module.yaml new file mode 100644 index 000000000000..1950b2692f62 --- /dev/null +++ b/src/modules/simulator/sensor_mag_sim/module.yaml @@ -0,0 +1,25 @@ +module_name: sensor_mag_sim +parameters: +- definitions: + SIM_MAG_OFFSET_X: + default: 0.0 + description: + short: simulated magnetometer X offset + type: float + unit: gauss + volatile: false + SIM_MAG_OFFSET_Y: + default: 0.0 + description: + short: simulated magnetometer Y offset + type: float + unit: gauss + volatile: false + SIM_MAG_OFFSET_Z: + default: 0.0 + description: + short: simulated magnetometer Z offset + type: float + unit: gauss + volatile: false + group: Simulator diff --git a/src/modules/simulator/sensor_mag_sim/parameters.c b/src/modules/simulator/sensor_mag_sim/parameters.c deleted file mode 100644 index f61bff443f6e..000000000000 --- a/src/modules/simulator/sensor_mag_sim/parameters.c +++ /dev/null @@ -1,56 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * simulated magnetometer X offset - * - * @unit gauss - * @group Simulator - */ -PARAM_DEFINE_FLOAT(SIM_MAG_OFFSET_X, 0.0f); - -/** - * simulated magnetometer Y offset - * - * @unit gauss - * @group Simulator - */ -PARAM_DEFINE_FLOAT(SIM_MAG_OFFSET_Y, 0.0f); - -/** - * simulated magnetometer Z offset - * - * @unit gauss - * @group Simulator - */ -PARAM_DEFINE_FLOAT(SIM_MAG_OFFSET_Z, 0.0f); diff --git a/src/modules/simulator/simulator_params.c b/src/modules/simulator/simulator_params.c deleted file mode 100644 index 4a6c211b068e..000000000000 --- a/src/modules/simulator/simulator_params.c +++ /dev/null @@ -1,40 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file simulator_params.c - * - * Parameters of software in the loop - * - * @author Mohamed Abdelkader - */ diff --git a/src/modules/temperature_compensation/CMakeLists.txt b/src/modules/temperature_compensation/CMakeLists.txt index 50e6a181e059..991ca4ebb471 100644 --- a/src/modules/temperature_compensation/CMakeLists.txt +++ b/src/modules/temperature_compensation/CMakeLists.txt @@ -41,6 +41,8 @@ px4_add_module( temperature_calibration/baro.cpp temperature_calibration/gyro.cpp temperature_calibration/task.cpp + MODULE_CONFIG + module.yaml DEPENDS mathlib ) diff --git a/src/modules/temperature_compensation/module.yaml b/src/modules/temperature_compensation/module.yaml new file mode 100644 index 000000000000..cb724d6bafeb --- /dev/null +++ b/src/modules/temperature_compensation/module.yaml @@ -0,0 +1,1201 @@ +module_name: temperature_compensation +parameters: + - definitions: + TC_A_ENABLE: + default: 0 + description: + short: Thermal compensation for accelerometer sensors + reboot_required: true + type: boolean + volatile: false + TC_A0_ID: + category: System + default: 0 + description: + short: ID of Accelerometer that the calibration is for + type: int32 + volatile: false + TC_A0_TMAX: + category: System + default: 100.0 + description: + short: Accelerometer calibration maximum temperature + type: float + volatile: false + TC_A0_TMIN: + category: System + default: 0.0 + description: + short: Accelerometer calibration minimum temperature + type: float + volatile: false + TC_A0_TREF: + category: System + default: 25.0 + description: + short: Accelerometer calibration reference temperature + type: float + volatile: false + TC_A0_X0_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - X axis + type: float + volatile: false + TC_A0_X0_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - Y axis + type: float + volatile: false + TC_A0_X0_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - Z axis + type: float + volatile: false + TC_A0_X1_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - X axis + type: float + volatile: false + TC_A0_X1_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - Y axis + type: float + volatile: false + TC_A0_X1_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - Z axis + type: float + volatile: false + TC_A0_X2_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - X axis + type: float + volatile: false + TC_A0_X2_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - Y axis + type: float + volatile: false + TC_A0_X2_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - Z axis + type: float + volatile: false + TC_A0_X3_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - X axis + type: float + volatile: false + TC_A0_X3_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - Y axis + type: float + volatile: false + TC_A0_X3_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - Z axis + type: float + volatile: false + TC_A1_ID: + category: System + default: 0 + description: + short: ID of Accelerometer that the calibration is for + type: int32 + volatile: false + TC_A1_TMAX: + category: System + default: 100.0 + description: + short: Accelerometer calibration maximum temperature + type: float + volatile: false + TC_A1_TMIN: + category: System + default: 0.0 + description: + short: Accelerometer calibration minimum temperature + type: float + volatile: false + TC_A1_TREF: + category: System + default: 25.0 + description: + short: Accelerometer calibration reference temperature + type: float + volatile: false + TC_A1_X0_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - X axis + type: float + volatile: false + TC_A1_X0_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - Y axis + type: float + volatile: false + TC_A1_X0_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - Z axis + type: float + volatile: false + TC_A1_X1_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - X axis + type: float + volatile: false + TC_A1_X1_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - Y axis + type: float + volatile: false + TC_A1_X1_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - Z axis + type: float + volatile: false + TC_A1_X2_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - X axis + type: float + volatile: false + TC_A1_X2_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - Y axis + type: float + volatile: false + TC_A1_X2_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - Z axis + type: float + volatile: false + TC_A1_X3_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - X axis + type: float + volatile: false + TC_A1_X3_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - Y axis + type: float + volatile: false + TC_A1_X3_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - Z axis + type: float + volatile: false + TC_A2_ID: + category: System + default: 0 + description: + short: ID of Accelerometer that the calibration is for + type: int32 + volatile: false + TC_A2_TMAX: + category: System + default: 100.0 + description: + short: Accelerometer calibration maximum temperature + type: float + volatile: false + TC_A2_TMIN: + category: System + default: 0.0 + description: + short: Accelerometer calibration minimum temperature + type: float + volatile: false + TC_A2_TREF: + category: System + default: 25.0 + description: + short: Accelerometer calibration reference temperature + type: float + volatile: false + TC_A2_X0_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - X axis + type: float + volatile: false + TC_A2_X0_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - Y axis + type: float + volatile: false + TC_A2_X0_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - Z axis + type: float + volatile: false + TC_A2_X1_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - X axis + type: float + volatile: false + TC_A2_X1_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - Y axis + type: float + volatile: false + TC_A2_X1_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - Z axis + type: float + volatile: false + TC_A2_X2_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - X axis + type: float + volatile: false + TC_A2_X2_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - Y axis + type: float + volatile: false + TC_A2_X2_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - Z axis + type: float + volatile: false + TC_A2_X3_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - X axis + type: float + volatile: false + TC_A2_X3_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - Y axis + type: float + volatile: false + TC_A2_X3_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - Z axis + type: float + volatile: false + TC_A3_ID: + category: System + default: 0 + description: + short: ID of Accelerometer that the calibration is for + type: int32 + volatile: false + TC_A3_TMAX: + category: System + default: 100.0 + description: + short: Accelerometer calibration maximum temperature + type: float + volatile: false + TC_A3_TMIN: + category: System + default: 0.0 + description: + short: Accelerometer calibration minimum temperature + type: float + volatile: false + TC_A3_TREF: + category: System + default: 25.0 + description: + short: Accelerometer calibration reference temperature + type: float + volatile: false + TC_A3_X0_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - X axis + type: float + volatile: false + TC_A3_X0_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - Y axis + type: float + volatile: false + TC_A3_X0_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^0 polynomial coefficient - Z axis + type: float + volatile: false + TC_A3_X1_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - X axis + type: float + volatile: false + TC_A3_X1_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - Y axis + type: float + volatile: false + TC_A3_X1_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^1 polynomial coefficient - Z axis + type: float + volatile: false + TC_A3_X2_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - X axis + type: float + volatile: false + TC_A3_X2_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - Y axis + type: float + volatile: false + TC_A3_X2_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^2 polynomial coefficient - Z axis + type: float + volatile: false + TC_A3_X3_0: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - X axis + type: float + volatile: false + TC_A3_X3_1: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - Y axis + type: float + volatile: false + TC_A3_X3_2: + category: System + default: 0.0 + description: + short: Accelerometer offset temperature ^3 polynomial coefficient - Z axis + type: float + volatile: false + TC_B_ENABLE: + default: 0 + description: + short: Thermal compensation for barometric pressure sensors + reboot_required: true + type: boolean + volatile: false + TC_B0_ID: + category: System + default: 0 + description: + short: ID of Barometer that the calibration is for + type: int32 + volatile: false + TC_B0_TMAX: + category: System + default: 75.0 + description: + short: Barometer calibration maximum temperature + type: float + volatile: false + TC_B0_TMIN: + category: System + default: 5.0 + description: + short: Barometer calibration minimum temperature + type: float + volatile: false + TC_B0_TREF: + category: System + default: 40.0 + description: + short: Barometer calibration reference temperature + type: float + volatile: false + TC_B0_X0: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^0 polynomial coefficient + type: float + volatile: false + TC_B0_X1: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^1 polynomial coefficients + type: float + volatile: false + TC_B0_X2: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^2 polynomial coefficient + type: float + volatile: false + TC_B0_X3: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^3 polynomial coefficient + type: float + volatile: false + TC_B0_X4: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^4 polynomial coefficient + type: float + volatile: false + TC_B0_X5: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^5 polynomial coefficient + type: float + volatile: false + TC_B1_ID: + category: System + default: 0 + description: + short: ID of Barometer that the calibration is for + type: int32 + volatile: false + TC_B1_TMAX: + category: System + default: 75.0 + description: + short: Barometer calibration maximum temperature + type: float + volatile: false + TC_B1_TMIN: + category: System + default: 5.0 + description: + short: Barometer calibration minimum temperature + type: float + volatile: false + TC_B1_TREF: + category: System + default: 40.0 + description: + short: Barometer calibration reference temperature + type: float + volatile: false + TC_B1_X0: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^0 polynomial coefficient + type: float + volatile: false + TC_B1_X1: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^1 polynomial coefficients + type: float + volatile: false + TC_B1_X2: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^2 polynomial coefficient + type: float + volatile: false + TC_B1_X3: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^3 polynomial coefficient + type: float + volatile: false + TC_B1_X4: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^4 polynomial coefficient + type: float + volatile: false + TC_B1_X5: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^5 polynomial coefficient + type: float + volatile: false + TC_B2_ID: + category: System + default: 0 + description: + short: ID of Barometer that the calibration is for + type: int32 + volatile: false + TC_B2_TMAX: + category: System + default: 75.0 + description: + short: Barometer calibration maximum temperature + type: float + volatile: false + TC_B2_TMIN: + category: System + default: 5.0 + description: + short: Barometer calibration minimum temperature + type: float + volatile: false + TC_B2_TREF: + category: System + default: 40.0 + description: + short: Barometer calibration reference temperature + type: float + volatile: false + TC_B2_X0: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^0 polynomial coefficient + type: float + volatile: false + TC_B2_X1: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^1 polynomial coefficients + type: float + volatile: false + TC_B2_X2: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^2 polynomial coefficient + type: float + volatile: false + TC_B2_X3: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^3 polynomial coefficient + type: float + volatile: false + TC_B2_X4: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^4 polynomial coefficient + type: float + volatile: false + TC_B2_X5: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^5 polynomial coefficient + type: float + volatile: false + TC_B3_ID: + category: System + default: 0 + description: + short: ID of Barometer that the calibration is for + type: int32 + volatile: false + TC_B3_TMAX: + category: System + default: 75.0 + description: + short: Barometer calibration maximum temperature + type: float + volatile: false + TC_B3_TMIN: + category: System + default: 5.0 + description: + short: Barometer calibration minimum temperature + type: float + volatile: false + TC_B3_TREF: + category: System + default: 40.0 + description: + short: Barometer calibration reference temperature + type: float + volatile: false + TC_B3_X0: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^0 polynomial coefficient + type: float + volatile: false + TC_B3_X1: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^1 polynomial coefficients + type: float + volatile: false + TC_B3_X2: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^2 polynomial coefficient + type: float + volatile: false + TC_B3_X3: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^3 polynomial coefficient + type: float + volatile: false + TC_B3_X4: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^4 polynomial coefficient + type: float + volatile: false + TC_B3_X5: + category: System + default: 0.0 + description: + short: Barometer offset temperature ^5 polynomial coefficient + type: float + volatile: false + TC_G_ENABLE: + default: 0 + description: + short: Thermal compensation for rate gyro sensors + reboot_required: true + type: boolean + volatile: false + TC_G0_ID: + category: System + default: 0 + description: + short: ID of Gyro that the calibration is for + type: int32 + volatile: false + TC_G0_TMAX: + category: System + default: 100.0 + description: + short: Gyro calibration maximum temperature + type: float + volatile: false + TC_G0_TMIN: + category: System + default: 0.0 + description: + short: Gyro calibration minimum temperature + type: float + volatile: false + TC_G0_TREF: + category: System + default: 25.0 + description: + short: Gyro calibration reference temperature + type: float + volatile: false + TC_G0_X0_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - X axis + type: float + volatile: false + TC_G0_X0_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - Y axis + type: float + volatile: false + TC_G0_X0_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - Z axis + type: float + volatile: false + TC_G0_X1_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - X axis + type: float + volatile: false + TC_G0_X1_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - Y axis + type: float + volatile: false + TC_G0_X1_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - Z axis + type: float + volatile: false + TC_G0_X2_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - X axis + type: float + volatile: false + TC_G0_X2_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - Y axis + type: float + volatile: false + TC_G0_X2_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - Z axis + type: float + volatile: false + TC_G0_X3_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - X axis + type: float + volatile: false + TC_G0_X3_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - Y axis + type: float + volatile: false + TC_G0_X3_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - Z axis + type: float + volatile: false + TC_G1_ID: + category: System + default: 0 + description: + short: ID of Gyro that the calibration is for + type: int32 + volatile: false + TC_G1_TMAX: + category: System + default: 100.0 + description: + short: Gyro calibration maximum temperature + type: float + volatile: false + TC_G1_TMIN: + category: System + default: 0.0 + description: + short: Gyro calibration minimum temperature + type: float + volatile: false + TC_G1_TREF: + category: System + default: 25.0 + description: + short: Gyro calibration reference temperature + type: float + volatile: false + TC_G1_X0_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - X axis + type: float + volatile: false + TC_G1_X0_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - Y axis + type: float + volatile: false + TC_G1_X0_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - Z axis + type: float + volatile: false + TC_G1_X1_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - X axis + type: float + volatile: false + TC_G1_X1_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - Y axis + type: float + volatile: false + TC_G1_X1_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - Z axis + type: float + volatile: false + TC_G1_X2_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - X axis + type: float + volatile: false + TC_G1_X2_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - Y axis + type: float + volatile: false + TC_G1_X2_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - Z axis + type: float + volatile: false + TC_G1_X3_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - X axis + type: float + volatile: false + TC_G1_X3_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - Y axis + type: float + volatile: false + TC_G1_X3_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - Z axis + type: float + volatile: false + TC_G2_ID: + category: System + default: 0 + description: + short: ID of Gyro that the calibration is for + type: int32 + volatile: false + TC_G2_TMAX: + category: System + default: 100.0 + description: + short: Gyro calibration maximum temperature + type: float + volatile: false + TC_G2_TMIN: + category: System + default: 0.0 + description: + short: Gyro calibration minimum temperature + type: float + volatile: false + TC_G2_TREF: + category: System + default: 25.0 + description: + short: Gyro calibration reference temperature + type: float + volatile: false + TC_G2_X0_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - X axis + type: float + volatile: false + TC_G2_X0_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - Y axis + type: float + volatile: false + TC_G2_X0_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - Z axis + type: float + volatile: false + TC_G2_X1_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - X axis + type: float + volatile: false + TC_G2_X1_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - Y axis + type: float + volatile: false + TC_G2_X1_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - Z axis + type: float + volatile: false + TC_G2_X2_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - X axis + type: float + volatile: false + TC_G2_X2_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - Y axis + type: float + volatile: false + TC_G2_X2_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - Z axis + type: float + volatile: false + TC_G2_X3_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - X axis + type: float + volatile: false + TC_G2_X3_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - Y axis + type: float + volatile: false + TC_G2_X3_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - Z axis + type: float + volatile: false + TC_G3_ID: + category: System + default: 0 + description: + short: ID of Gyro that the calibration is for + type: int32 + volatile: false + TC_G3_TMAX: + category: System + default: 100.0 + description: + short: Gyro calibration maximum temperature + type: float + volatile: false + TC_G3_TMIN: + category: System + default: 0.0 + description: + short: Gyro calibration minimum temperature + type: float + volatile: false + TC_G3_TREF: + category: System + default: 25.0 + description: + short: Gyro calibration reference temperature + type: float + volatile: false + TC_G3_X0_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - X axis + type: float + volatile: false + TC_G3_X0_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - Y axis + type: float + volatile: false + TC_G3_X0_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^0 polynomial coefficient - Z axis + type: float + volatile: false + TC_G3_X1_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - X axis + type: float + volatile: false + TC_G3_X1_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - Y axis + type: float + volatile: false + TC_G3_X1_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^1 polynomial coefficient - Z axis + type: float + volatile: false + TC_G3_X2_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - X axis + type: float + volatile: false + TC_G3_X2_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - Y axis + type: float + volatile: false + TC_G3_X2_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^2 polynomial coefficient - Z axis + type: float + volatile: false + TC_G3_X3_0: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - X axis + type: float + volatile: false + TC_G3_X3_1: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - Y axis + type: float + volatile: false + TC_G3_X3_2: + category: System + default: 0.0 + description: + short: Gyro rate offset temperature ^3 polynomial coefficient - Z axis + type: float + volatile: false + group: Thermal Compensation diff --git a/src/modules/temperature_compensation/temp_comp_params_accel.c b/src/modules/temperature_compensation/temp_comp_params_accel.c deleted file mode 100644 index f42e7ac3aa5c..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_accel.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Thermal compensation for accelerometer sensors. - * - * @group Thermal Compensation - * @reboot_required true - * @boolean - */ -PARAM_DEFINE_INT32(TC_A_ENABLE, 0); diff --git a/src/modules/temperature_compensation/temp_comp_params_accel_0.c b/src/modules/temperature_compensation/temp_comp_params_accel_0.c deleted file mode 100644 index 1b4f03471e91..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_accel_0.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Accelerometer 0 */ - -/** - * ID of Accelerometer that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_A0_ID, 0); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X3_0, 0.0f); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X3_1, 0.0f); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X3_2, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X2_0, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X2_1, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X2_2, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X1_0, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X1_1, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X1_2, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X0_0, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X0_1, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_X0_2, 0.0f); - -/** - * Accelerometer calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_TREF, 25.0f); - -/** - * Accelerometer calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_TMIN, 0.0f); - -/** - * Accelerometer calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A0_TMAX, 100.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_accel_1.c b/src/modules/temperature_compensation/temp_comp_params_accel_1.c deleted file mode 100644 index ed3d0b0a3964..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_accel_1.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Accelerometer 1 */ - -/** - * ID of Accelerometer that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_A1_ID, 0); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X3_0, 0.0f); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X3_1, 0.0f); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X3_2, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X2_0, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X2_1, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X2_2, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X1_0, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X1_1, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X1_2, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X0_0, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X0_1, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_X0_2, 0.0f); - -/** - * Accelerometer calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_TREF, 25.0f); - -/** - * Accelerometer calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_TMIN, 0.0f); - -/** - * Accelerometer calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A1_TMAX, 100.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_accel_2.c b/src/modules/temperature_compensation/temp_comp_params_accel_2.c deleted file mode 100644 index 0155a2ab546f..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_accel_2.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Accelerometer 2 */ - -/** - * ID of Accelerometer that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_A2_ID, 0); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X3_0, 0.0f); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X3_1, 0.0f); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X3_2, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X2_0, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X2_1, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X2_2, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X1_0, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X1_1, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X1_2, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X0_0, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X0_1, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_X0_2, 0.0f); - -/** - * Accelerometer calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_TREF, 25.0f); - -/** - * Accelerometer calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_TMIN, 0.0f); - -/** - * Accelerometer calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A2_TMAX, 100.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_accel_3.c b/src/modules/temperature_compensation/temp_comp_params_accel_3.c deleted file mode 100644 index f3d35cbedc2b..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_accel_3.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Accelerometer 3 */ - -/** - * ID of Accelerometer that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_A3_ID, 0); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X3_0, 0.0f); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X3_1, 0.0f); - -/** - * Accelerometer offset temperature ^3 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X3_2, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X2_0, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X2_1, 0.0f); - -/** - * Accelerometer offset temperature ^2 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X2_2, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X1_0, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X1_1, 0.0f); - -/** - * Accelerometer offset temperature ^1 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X1_2, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X0_0, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X0_1, 0.0f); - -/** - * Accelerometer offset temperature ^0 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_X0_2, 0.0f); - -/** - * Accelerometer calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_TREF, 25.0f); - -/** - * Accelerometer calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_TMIN, 0.0f); - -/** - * Accelerometer calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_A3_TMAX, 100.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_baro.c b/src/modules/temperature_compensation/temp_comp_params_baro.c deleted file mode 100644 index 1e5a1add2210..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_baro.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Thermal compensation for barometric pressure sensors. - * - * @group Thermal Compensation - * @reboot_required true - * @boolean - */ -PARAM_DEFINE_INT32(TC_B_ENABLE, 0); diff --git a/src/modules/temperature_compensation/temp_comp_params_baro_0.c b/src/modules/temperature_compensation/temp_comp_params_baro_0.c deleted file mode 100644 index 1fef48220e1e..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_baro_0.c +++ /dev/null @@ -1,114 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Barometer 0 */ - -/** - * ID of Barometer that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_B0_ID, 0); - -/** - * Barometer offset temperature ^5 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_X5, 0.0f); - -/** - * Barometer offset temperature ^4 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_X4, 0.0f); - -/** - * Barometer offset temperature ^3 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_X3, 0.0f); - -/** - * Barometer offset temperature ^2 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_X2, 0.0f); - -/** - * Barometer offset temperature ^1 polynomial coefficients. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_X1, 0.0f); - -/** - * Barometer offset temperature ^0 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_X0, 0.0f); - -/** - * Barometer calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_TREF, 40.0f); - -/** - * Barometer calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_TMIN, 5.0f); - -/** - * Barometer calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B0_TMAX, 75.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_baro_1.c b/src/modules/temperature_compensation/temp_comp_params_baro_1.c deleted file mode 100644 index 2f0fcda4925e..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_baro_1.c +++ /dev/null @@ -1,114 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Barometer 1 */ - -/** - * ID of Barometer that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_B1_ID, 0); - -/** - * Barometer offset temperature ^5 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_X5, 0.0f); - -/** - * Barometer offset temperature ^4 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_X4, 0.0f); - -/** - * Barometer offset temperature ^3 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_X3, 0.0f); - -/** - * Barometer offset temperature ^2 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_X2, 0.0f); - -/** - * Barometer offset temperature ^1 polynomial coefficients. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_X1, 0.0f); - -/** - * Barometer offset temperature ^0 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_X0, 0.0f); - -/** - * Barometer calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_TREF, 40.0f); - -/** - * Barometer calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_TMIN, 5.0f); - -/** - * Barometer calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B1_TMAX, 75.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_baro_2.c b/src/modules/temperature_compensation/temp_comp_params_baro_2.c deleted file mode 100644 index b32d9ef535f9..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_baro_2.c +++ /dev/null @@ -1,114 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Barometer 2 */ - -/** - * ID of Barometer that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_B2_ID, 0); - -/** - * Barometer offset temperature ^5 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_X5, 0.0f); - -/** - * Barometer offset temperature ^4 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_X4, 0.0f); - -/** - * Barometer offset temperature ^3 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_X3, 0.0f); - -/** - * Barometer offset temperature ^2 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_X2, 0.0f); - -/** - * Barometer offset temperature ^1 polynomial coefficients. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_X1, 0.0f); - -/** - * Barometer offset temperature ^0 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_X0, 0.0f); - -/** - * Barometer calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_TREF, 40.0f); - -/** - * Barometer calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_TMIN, 5.0f); - -/** - * Barometer calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B2_TMAX, 75.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_baro_3.c b/src/modules/temperature_compensation/temp_comp_params_baro_3.c deleted file mode 100644 index a514e783f7e9..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_baro_3.c +++ /dev/null @@ -1,114 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Barometer 3 */ - -/** - * ID of Barometer that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_B3_ID, 0); - -/** - * Barometer offset temperature ^5 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_X5, 0.0f); - -/** - * Barometer offset temperature ^4 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_X4, 0.0f); - -/** - * Barometer offset temperature ^3 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_X3, 0.0f); - -/** - * Barometer offset temperature ^2 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_X2, 0.0f); - -/** - * Barometer offset temperature ^1 polynomial coefficients. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_X1, 0.0f); - -/** - * Barometer offset temperature ^0 polynomial coefficient. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_X0, 0.0f); - -/** - * Barometer calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_TREF, 40.0f); - -/** - * Barometer calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_TMIN, 5.0f); - -/** - * Barometer calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_B3_TMAX, 75.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_gyro.c b/src/modules/temperature_compensation/temp_comp_params_gyro.c deleted file mode 100644 index cd321dd84cb1..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_gyro.c +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * Thermal compensation for rate gyro sensors. - * - * @group Thermal Compensation - * @reboot_required true - * @boolean - */ -PARAM_DEFINE_INT32(TC_G_ENABLE, 0); diff --git a/src/modules/temperature_compensation/temp_comp_params_gyro_0.c b/src/modules/temperature_compensation/temp_comp_params_gyro_0.c deleted file mode 100644 index 7f05b14054a1..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_gyro_0.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Gyro 0 */ - -/** - * ID of Gyro that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_G0_ID, 0); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X3_0, 0.0f); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X3_1, 0.0f); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X3_2, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X2_0, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X2_1, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X2_2, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X1_0, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X1_1, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X1_2, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X0_0, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X0_1, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_X0_2, 0.0f); - -/** - * Gyro calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_TREF, 25.0f); - -/** - * Gyro calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_TMIN, 0.0f); - -/** - * Gyro calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G0_TMAX, 100.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_gyro_1.c b/src/modules/temperature_compensation/temp_comp_params_gyro_1.c deleted file mode 100644 index b86dea223ab6..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_gyro_1.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Gyro 1 */ - -/** - * ID of Gyro that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_G1_ID, 0); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X3_0, 0.0f); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X3_1, 0.0f); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X3_2, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X2_0, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X2_1, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X2_2, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X1_0, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X1_1, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X1_2, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X0_0, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X0_1, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_X0_2, 0.0f); - -/** - * Gyro calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_TREF, 25.0f); - -/** - * Gyro calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_TMIN, 0.0f); - -/** - * Gyro calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G1_TMAX, 100.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_gyro_2.c b/src/modules/temperature_compensation/temp_comp_params_gyro_2.c deleted file mode 100644 index ed203776422e..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_gyro_2.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Gyro 2 */ - -/** - * ID of Gyro that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_G2_ID, 0); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X3_0, 0.0f); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X3_1, 0.0f); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X3_2, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X2_0, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X2_1, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X2_2, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X1_0, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X1_1, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X1_2, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X0_0, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X0_1, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_X0_2, 0.0f); - -/** - * Gyro calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_TREF, 25.0f); - -/** - * Gyro calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_TMIN, 0.0f); - -/** - * Gyro calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G2_TMAX, 100.0f); diff --git a/src/modules/temperature_compensation/temp_comp_params_gyro_3.c b/src/modules/temperature_compensation/temp_comp_params_gyro_3.c deleted file mode 100644 index a0ed93a4cd73..000000000000 --- a/src/modules/temperature_compensation/temp_comp_params_gyro_3.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/* Gyro 3 */ - -/** - * ID of Gyro that the calibration is for. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_INT32(TC_G3_ID, 0); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X3_0, 0.0f); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X3_1, 0.0f); - -/** - * Gyro rate offset temperature ^3 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X3_2, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X2_0, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X2_1, 0.0f); - -/** - * Gyro rate offset temperature ^2 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X2_2, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X1_0, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X1_1, 0.0f); - -/** - * Gyro rate offset temperature ^1 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X1_2, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - X axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X0_0, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - Y axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X0_1, 0.0f); - -/** - * Gyro rate offset temperature ^0 polynomial coefficient - Z axis. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_X0_2, 0.0f); - -/** - * Gyro calibration reference temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_TREF, 25.0f); - -/** - * Gyro calibration minimum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_TMIN, 0.0f); - -/** - * Gyro calibration maximum temperature. - * - * @group Thermal Compensation - * @category system - */ -PARAM_DEFINE_FLOAT(TC_G3_TMAX, 100.0f); diff --git a/src/modules/uuv_att_control/CMakeLists.txt b/src/modules/uuv_att_control/CMakeLists.txt index 37dc0d728cf1..1dbdf508bb63 100644 --- a/src/modules/uuv_att_control/CMakeLists.txt +++ b/src/modules/uuv_att_control/CMakeLists.txt @@ -37,4 +37,6 @@ px4_add_module( COMPILE_FLAGS SRCS uuv_att_control.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/modules/uuv_att_control/module.yaml b/src/modules/uuv_att_control/module.yaml new file mode 100644 index 000000000000..8d896cdbef5e --- /dev/null +++ b/src/modules/uuv_att_control/module.yaml @@ -0,0 +1,90 @@ +module_name: uuv_att_control +parameters: + - definitions: + UUV_DIRCT_PITCH: + default: 0.0 + description: + short: Direct pitch input + type: float + volatile: false + UUV_DIRCT_ROLL: + default: 0.0 + description: + short: Direct roll input + type: float + volatile: false + UUV_DIRCT_THRUST: + default: 0.0 + description: + short: Direct thrust input + type: float + volatile: false + UUV_DIRCT_YAW: + default: 0.0 + description: + short: Direct yaw input + type: float + volatile: false + UUV_INPUT_MODE: + default: 0 + description: + short: Select Input Mode + type: enum + values: + 0: use Attitude Setpoints + 1: Direct Feedthrough + volatile: false + UUV_PITCH_D: + decimal: 2 + default: 2.0 + description: + short: Pitch differential gain + type: float + volatile: false + UUV_PITCH_P: + decimal: 2 + default: 4.0 + description: + short: Pitch proportional gain + type: float + volatile: false + UUV_ROLL_D: + decimal: 2 + default: 1.5 + description: + short: Roll differential gain + type: float + volatile: false + UUV_ROLL_P: + decimal: 2 + default: 4.0 + description: + short: Roll proportional gain + type: float + volatile: false + UUV_YAW_D: + decimal: 2 + default: 2.0 + description: + short: Yaw differential gain + type: float + volatile: false + UUV_YAW_P: + decimal: 2 + default: 4.0 + description: + short: Yawh proportional gain + type: float + volatile: false + group: UUV Attitude Control + - definitions: + UUV_SKIP_CTRL: + default: 0 + description: + short: Skip the controller + type: enum + values: + 0: use the module's controller + 1: skip the controller and feedthrough the setpoints + volatile: false + group: Miscellaneous diff --git a/src/modules/uuv_att_control/uuv_att_control_params.c b/src/modules/uuv_att_control/uuv_att_control_params.c deleted file mode 100644 index fdad0b3d88b4..000000000000 --- a/src/modules/uuv_att_control/uuv_att_control_params.c +++ /dev/null @@ -1,150 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file uuv_att_control_params.c - * - * Parameters defined by the attitude control task for unmanned underwater vehicles (UUVs) - * - * This is a modification of the fixed wing/ground rover params and it is designed for ground rovers. - * It has been developed starting from the fw module, simplified and improved with dedicated items. - * - * All the ackowledgments and credits for the fw wing/rover app are reported in those files. - * - * @author Daniel Duecker - */ - -/* - * Controller parameters, accessible via MAVLink - * - */ - -// Roll gains -/** - * Roll proportional gain - * - * @group UUV Attitude Control - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(UUV_ROLL_P, 4.0f); - -/** - * Roll differential gain - * - * @group UUV Attitude Control - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(UUV_ROLL_D, 1.5f); - - -// Pitch gains -/** - * Pitch proportional gain - * - * @group UUV Attitude Control - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(UUV_PITCH_P, 4.0f); - -/** - * Pitch differential gain - * - * @group UUV Attitude Control - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(UUV_PITCH_D, 2.0f); - - -// Yaw gains -/** - * Yawh proportional gain - * - * @group UUV Attitude Control - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(UUV_YAW_P, 4.0f); - -/** - * Yaw differential gain - * - * @group UUV Attitude Control - * @decimal 2 - */ -PARAM_DEFINE_FLOAT(UUV_YAW_D, 2.0f); - - -// Input Modes -/** - * Select Input Mode - * - * @value 0 use Attitude Setpoints - * @value 1 Direct Feedthrough - * @group UUV Attitude Control - */ -PARAM_DEFINE_INT32(UUV_INPUT_MODE, 0); - -/** - * Skip the controller - * - * @value 0 use the module's controller - * @value 1 skip the controller and feedthrough the setpoints - */ -PARAM_DEFINE_INT32(UUV_SKIP_CTRL, 0); - -/** - * Direct roll input - * - * @group UUV Attitude Control - */ -PARAM_DEFINE_FLOAT(UUV_DIRCT_ROLL, 0.0f); - -/** - * Direct pitch input - * - * @group UUV Attitude Control - */ -PARAM_DEFINE_FLOAT(UUV_DIRCT_PITCH, 0.0f); - -/** - * Direct yaw input - * - * @group UUV Attitude Control - */ -PARAM_DEFINE_FLOAT(UUV_DIRCT_YAW, 0.0f); - -/** - * Direct thrust input - * - * @group UUV Attitude Control - */ -PARAM_DEFINE_FLOAT(UUV_DIRCT_THRUST, 0.0f); diff --git a/src/modules/uuv_pos_control/CMakeLists.txt b/src/modules/uuv_pos_control/CMakeLists.txt index f97dd0ea42d4..63efbed07875 100644 --- a/src/modules/uuv_pos_control/CMakeLists.txt +++ b/src/modules/uuv_pos_control/CMakeLists.txt @@ -37,4 +37,6 @@ px4_add_module( COMPILE_FLAGS SRCS uuv_pos_control.cpp + MODULE_CONFIG + module.yaml ) diff --git a/src/modules/uuv_pos_control/module.yaml b/src/modules/uuv_pos_control/module.yaml new file mode 100644 index 000000000000..51dacb9d369e --- /dev/null +++ b/src/modules/uuv_pos_control/module.yaml @@ -0,0 +1,49 @@ +module_name: uuv_pos_control +parameters: + - definitions: + UUV_GAIN_X_D: + default: 0.2 + description: + short: Gain of D controller X + type: float + volatile: false + UUV_GAIN_X_P: + default: 1.0 + description: + short: Gain of P controller X + type: float + volatile: false + UUV_GAIN_Y_D: + default: 0.2 + description: + short: Gain of D controller Y + type: float + volatile: false + UUV_GAIN_Y_P: + default: 1.0 + description: + short: Gain of P controller Y + type: float + volatile: false + UUV_GAIN_Z_D: + default: 0.2 + description: + short: Gain of D controller Z + type: float + volatile: false + UUV_GAIN_Z_P: + default: 1.0 + description: + short: Gain of P controller Z + type: float + volatile: false + UUV_STAB_MODE: + default: 1 + description: + short: Stabilization mode(1) or Position Control(0) + type: enum + values: + 0: Position Control + 1: Stabilization Mode + volatile: false + group: UUV Position Control diff --git a/src/modules/uuv_pos_control/uuv_pos_control_params.c b/src/modules/uuv_pos_control/uuv_pos_control_params.c deleted file mode 100644 index d3532edd43b8..000000000000 --- a/src/modules/uuv_pos_control/uuv_pos_control_params.c +++ /dev/null @@ -1,97 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2020 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file uuv_pos_control_params.c - * - * Parameters defined by the position control task for unmanned underwater vehicles (UUVs) - * - * This is a modification of the fixed wing/ground rover params and it is designed for ground rovers. - * It has been developed starting from the fw module, simplified and improved with dedicated items. - * - * All the ackowledgments and credits for the fw wing/rover app are reported in those files. - * - * @author Tim Hansen - * @author Daniel Duecker - */ - -/* - * Controller parameters, accessible via MAVLink - * - */ -/** - * Gain of P controller X - * - * @group UUV Position Control - */ -PARAM_DEFINE_FLOAT(UUV_GAIN_X_P, 1.0f); -/** - * Gain of P controller Y - * - * @group UUV Position Control - */ -PARAM_DEFINE_FLOAT(UUV_GAIN_Y_P, 1.0f); -/** - * Gain of P controller Z - * - * @group UUV Position Control - */ -PARAM_DEFINE_FLOAT(UUV_GAIN_Z_P, 1.0f); - -/** - * Gain of D controller X - * - * @group UUV Position Control - */ -PARAM_DEFINE_FLOAT(UUV_GAIN_X_D, 0.2f); -/** - * Gain of D controller Y - * - * @group UUV Position Control - */ -PARAM_DEFINE_FLOAT(UUV_GAIN_Y_D, 0.2f); -/** - * Gain of D controller Z - * - * @group UUV Position Control - */ -PARAM_DEFINE_FLOAT(UUV_GAIN_Z_D, 0.2f); - -/** - * Stabilization mode(1) or Position Control(0) - * - * @value 0 Position Control - * @value 1 Stabilization Mode - * @group UUV Position Control - */ -PARAM_DEFINE_INT32(UUV_STAB_MODE, 1); diff --git a/src/modules/vtol_att_control/CMakeLists.txt b/src/modules/vtol_att_control/CMakeLists.txt index 517828377f55..b038507b5e6b 100644 --- a/src/modules/vtol_att_control/CMakeLists.txt +++ b/src/modules/vtol_att_control/CMakeLists.txt @@ -39,6 +39,8 @@ px4_add_module( vtol_type.cpp tailsitter.cpp standard.cpp + MODULE_CONFIG + module.yaml DEPENDS SlewRate ) diff --git a/src/modules/vtol_att_control/module.yaml b/src/modules/vtol_att_control/module.yaml new file mode 100644 index 000000000000..1f78f67c6904 --- /dev/null +++ b/src/modules/vtol_att_control/module.yaml @@ -0,0 +1,404 @@ +module_name: vtol_att_control +parameters: + - definitions: + VT_B_REV_DEL: + decimal: 2 + default: 0.0 + description: + long: Set this to a value greater than 0 to give the motor time to spin down. unit s + short: Delay in seconds before applying back transition throttle + increment: 1 + max: 10 + min: 0 + type: float + volatile: false + VT_B_REV_OUT: + decimal: 2 + default: 0.0 + description: + long: Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel Airbrakes need to be enables for your selected model/mixer + short: Output on airbrakes channel during back transition + increment: 0.01 + max: 1 + min: 0 + type: float + volatile: false + VT_B_TRANS_RAMP: + default: 3.0 + description: + long: This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage. + short: Back transition MC motor ramp up time + max: 20.0 + min: 0.0 + type: float + unit: s + volatile: false + VT_FWD_THRUST_EN: + default: 0 + description: + long: This technique can be used to avoid the plane having to pitch down in order to move forward. This prevents large, negative lift values being created when facing strong winds. Fixed-wing forward actuators refers to puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL). Only active if demaded down pitch is below VT_PITCH_MIN, and uses VT_FWD_THRUST_SC to get from demanded down pitch to fixed-wing actuation. + short: Enable/disable usage of fixed-wing actuators in hover to generate forward force (instead of pitching down) + type: enum + values: + 0: Disable FW forward actuation in hover. + 1: Enable FW forward actuation in hover in altitude, position and auto modes (except LANDING). + 2: Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1. + 3: Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2. + 4: Enable FW forward actuation in hover in altitude, position and auto modes. + 5: Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1 (except LANDING). + 6: Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2 (except LANDING). + volatile: false + VT_FWD_THRUST_SC: + default: 0.7 + description: + long: Scale applied to the demanded down-pitch to get the fixed-wing forward actuation in hover mode. Only active if demaded down pitch is below VT_PITCH_MIN. Enabled via VT_FWD_THRUST_EN. + short: Fixed-wing actuator thrust scale for hover forward flight + max: 2.0 + min: 0.0 + type: float + volatile: false + VT_PSHER_RMP_DT: + decimal: 2 + default: 3.0 + description: + long: Defines the time window during which the pusher throttle will be ramped up linearly to VT_F_TRANS_THR during a transition to fixed wing mode. Zero or negative values will produce an instant throttle rise to VT_F_TRANS_THR. + short: Pusher throttle ramp up window + increment: 0.01 + max: 20 + type: float + volatile: false + VT_TILT_FW: + decimal: 3 + default: 1.0 + description: + short: Position of tilt servo in fw mode + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + volatile: false + VT_TILT_MC: + decimal: 3 + default: 0.0 + description: + short: Position of tilt servo in mc mode + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + volatile: false + VT_TILT_SPINUP: + decimal: 3 + default: 0.0 + description: + long: This specific tilt during spin-up is necessary for some systems whose motors otherwise don't spin-up freely. + short: Tilt actuator control value commanded when disarmed and during the first second after arming + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + volatile: false + VT_TILT_TRANS: + decimal: 3 + default: 0.3 + description: + short: Position of tilt servo in transition mode + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + volatile: false + VT_TRANS_P2_DUR: + decimal: 3 + default: 0.5 + description: + long: Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode. + short: Duration of front transition phase 2 + increment: 0.01 + max: 5.0 + min: 0.1 + type: float + unit: s + volatile: false + VT_ARSP_BLEND: + decimal: 2 + default: 8.0 + description: + long: Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable. + short: Transition blending airspeed + increment: 1 + max: 30.0 + min: 0.0 + type: float + unit: m/s + volatile: false + VT_ARSP_TRANS: + decimal: 2 + default: 10.0 + description: + long: Airspeed at which we can switch to fw mode + short: Transition airspeed + increment: 1 + max: 30.0 + min: 0.0 + type: float + unit: m/s + volatile: false + VT_B_DEC_FF: + decimal: 1 + default: 0.0 + description: + short: Backtransition deceleration setpoint to pitch feedforward gain + increment: 0.01 + max: 0.2 + min: 0 + type: float + unit: rad s^2/m + volatile: false + VT_B_DEC_I: + decimal: 1 + default: 0.1 + description: + short: Backtransition deceleration setpoint to pitch I gain + increment: 0.05 + max: 0.3 + min: 0 + type: float + unit: rad s/m + volatile: false + VT_B_DEC_MSS: + decimal: 2 + default: 2.0 + description: + long: The approximate deceleration during a back transition in m/s/s Used to calculate back transition distance in mission mode. A lower value will make the VTOL transition further from the destination waypoint. For standard vtol and tiltrotors a controller is used to track this value during the transition. + short: Approximate deceleration during back transition + increment: 0.1 + max: 10 + min: 0.5 + type: float + unit: m/s^2 + volatile: false + VT_B_TRANS_DUR: + decimal: 2 + default: 4.0 + description: + long: Time in seconds used for a back transition + short: Duration of a back transition + increment: 1 + max: 20.0 + min: 0.1 + type: float + unit: s + volatile: false + VT_B_TRANS_THR: + decimal: 2 + default: 0.0 + description: + long: 'standard vtol: pusher tailsitter, tiltrotor: main throttle Note for standard vtol: For ESCs and mixers that support reverse thrust on low PWM values set this to a negative value to apply active breaking For ESCs that support thrust reversal with a control channel please set VT_B_REV_OUT and set this to a positive value to apply active breaking' + short: Target throttle value for the transition to hover flight + increment: 0.01 + max: 1 + min: -1 + type: float + volatile: false + VT_ELEV_MC_LOCK: + default: 1 + description: + long: If set to 1 the control surfaces are locked at the disarmed value in multicopter mode. + short: Lock control surfaces in hover + type: boolean + volatile: false + VT_FW_ALT_ERR: + default: 0.0 + description: + long: Maximum negative altitude error for fixed wing flight. If the altitude drops below this value below the altitude setpoint the vehicle will transition back to MC mode and enter failsafe RTL. + short: Adaptive QuadChute + max: 200.0 + min: 0.0 + type: float + volatile: false + VT_FW_DIFTHR_EN: + decimal: 0 + default: 0 + description: + long: Set to 1 to enable differential thrust in fixed-wing flight. + short: Differential thrust in forwards flight + max: 1 + min: 0 + type: int32 + volatile: false + VT_FW_DIFTHR_SC: + decimal: 2 + default: 0.1 + description: + long: This factor specifies how the yaw input gets mapped to differential thrust in forwards flight. + short: Differential thrust scaling factor + increment: 0.1 + max: 1.0 + min: 0.0 + type: float + volatile: false + VT_FW_MIN_ALT: + default: 0.0 + description: + long: Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude the vehicle will transition back to MC mode and enter failsafe RTL + short: QuadChute Altitude + max: 200.0 + min: 0.0 + type: float + volatile: false + VT_FW_MOT_OFFID: + decimal: 0 + default: 0 + description: + short: The channel number of motors that must be turned off in fixed wing mode + increment: 1 + max: 12345678 + min: 0 + type: int32 + volatile: false + VT_FW_QC_P: + default: 0 + description: + long: Maximum pitch angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL + short: QuadChute Max Pitch + max: 180 + min: 0 + type: int32 + volatile: false + VT_FW_QC_R: + default: 0 + description: + long: Maximum roll angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL + short: QuadChute Max Roll + max: 180 + min: 0 + type: int32 + volatile: false + VT_F_TRANS_DUR: + decimal: 2 + default: 5.0 + description: + long: Time in seconds used for a transition + short: Duration of a front transition + increment: 1 + max: 20.0 + min: 0.1 + type: float + unit: s + volatile: false + VT_F_TRANS_THR: + decimal: 3 + default: 1.0 + description: + long: 'standard vtol: pusher tailsitter, tiltrotor: main throttle' + short: Target throttle value for the transition to fixed wing flight + increment: 0.01 + max: 1.0 + min: 0.0 + type: float + volatile: false + VT_F_TR_OL_TM: + default: 6.0 + description: + long: The duration of the front transition when there is no airspeed feedback available. + short: Airspeed less front transition time (open loop) + max: 30.0 + min: 1.0 + type: float + unit: s + volatile: false + VT_IDLE_PWM_MC: + decimal: 0 + default: 900 + description: + short: Idle speed of VTOL when in multicopter mode + increment: 1 + max: 2000 + min: 900 + type: int32 + unit: us + volatile: false + VT_LND_PITCH_MIN: + default: -5.0 + description: + long: Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to allow lower minimum pitch angles as it can avoid the wings generating too much lift and preventing the vehicle from sinking at the desired rate. + short: Minimum pitch angle during hover landing + max: 45.0 + min: -10.0 + type: float + volatile: false + VT_MC_ON_FMU: + default: 0 + description: + long: Set this parameter to true if the vehicle's hover motors are connected to the FMU (AUX) port. Not required for boards that only have a FMU, and no IO. Only applies for standard VTOL and tiltrotor. + short: Enable the usage of AUX outputs for hover motors + type: boolean + volatile: false + VT_MOT_ID: + decimal: 0 + default: 0 + description: + short: The channel number of motors which provide lift during hover + increment: 1 + max: 12345678 + min: 0 + type: int32 + volatile: false + VT_PITCH_MIN: + default: -5.0 + description: + long: Minimum pitch angle during hover flight. If the desired pitch angle is is lower than this value then the fixed-wing forward actuation can be used to compensate for the missing thrust in forward direction (see VT_FW_TRHUST_EN) + short: Minimum pitch angle during hover + max: 45.0 + min: -10.0 + type: float + volatile: false + VT_SPOILER_MC_LD: + decimal: 1 + default: 0.0 + description: + short: Spoiler setting while landing (hover) + increment: 0.05 + max: 1 + min: -1 + type: float + unit: norm + volatile: false + VT_TRANS_MIN_TM: + default: 2.0 + description: + long: Minimum time in seconds for front transition. + short: Front transition minimum time + max: 20.0 + min: 0.0 + type: float + unit: s + volatile: false + VT_TRANS_TIMEOUT: + decimal: 2 + default: 15.0 + description: + long: Time in seconds after which transition will be cancelled. Disabled if set to 0. + short: Front transition timeout + increment: 1 + max: 30.0 + min: 0.1 + type: float + unit: s + volatile: false + VT_TYPE: + decimal: 0 + default: 0 + description: + short: VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2) + max: 2 + min: 0 + reboot_required: true + type: enum + values: + 0: Tailsitter + 1: Tiltrotor + 2: Standard + volatile: false + group: VTOL Attitude Control diff --git a/src/modules/vtol_att_control/standard_params.c b/src/modules/vtol_att_control/standard_params.c deleted file mode 100644 index 3129619cecaa..000000000000 --- a/src/modules/vtol_att_control/standard_params.c +++ /dev/null @@ -1,129 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file standard_params.c - * Parameters for the standard VTOL controller. - * - * @author Simon Wilks - * @author Roman Bapst - */ - - -/** - * Enable/disable usage of fixed-wing actuators in hover to generate forward force (instead of pitching down). - * - * This technique can be used to avoid the plane having to pitch down in order to move forward. - * This prevents large, negative lift values being created when facing strong winds. - * Fixed-wing forward actuators refers to puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL). - * Only active if demaded down pitch is below VT_PITCH_MIN, and uses VT_FWD_THRUST_SC to get from - * demanded down pitch to fixed-wing actuation. - * - * @value 0 Disable FW forward actuation in hover. - * @value 1 Enable FW forward actuation in hover in altitude, position and auto modes (except LANDING). - * @value 2 Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1. - * @value 3 Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2. - * @value 4 Enable FW forward actuation in hover in altitude, position and auto modes. - * @value 5 Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1 (except LANDING). - * @value 6 Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2 (except LANDING). - * - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_FWD_THRUST_EN, 0); - -/** - * Fixed-wing actuator thrust scale for hover forward flight. - * - * Scale applied to the demanded down-pitch to get the fixed-wing forward actuation in hover mode. - * Only active if demaded down pitch is below VT_PITCH_MIN. - * Enabled via VT_FWD_THRUST_EN. - * - * @min 0.0 - * @max 2.0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_FWD_THRUST_SC, 0.7f); - -/** - * Back transition MC motor ramp up time - * - * This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage. - * - * @unit s - * @min 0.0 - * @max 20.0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_B_TRANS_RAMP, 3.0f); - -/** - * Output on airbrakes channel during back transition - * - * Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel - * Airbrakes need to be enables for your selected model/mixer - * - * @min 0 - * @max 1 - * @increment 0.01 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_B_REV_OUT, 0.0f); - - -/** - * Delay in seconds before applying back transition throttle - * - * Set this to a value greater than 0 to give the motor time to spin down. - * - * unit s - * @min 0 - * @max 10 - * @increment 1 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_B_REV_DEL, 0.0f); - -/** - * Pusher throttle ramp up window - * - * Defines the time window during which the pusher throttle will be ramped up linearly to VT_F_TRANS_THR during a transition - * to fixed wing mode. Zero or negative values will produce an instant throttle rise to VT_F_TRANS_THR. - * - * @max 20 - * @increment 0.01 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_PSHER_RMP_DT, 3.0f); diff --git a/src/modules/vtol_att_control/tailsitter_params.c b/src/modules/vtol_att_control/tailsitter_params.c deleted file mode 100644 index 34b17b0025bd..000000000000 --- a/src/modules/vtol_att_control/tailsitter_params.c +++ /dev/null @@ -1,55 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file tailsitter_params.c - * Parameters for vtol attitude controller. - * - * @author Roman Bapst - * @author David Vorsin - */ - -/** - * Duration of front transition phase 2 - * - * Time in seconds it should take for the rotors to rotate forward completely from the point - * when the plane has picked up enough airspeed and is ready to go into fixed wind mode. - * - * @unit s - * @min 0.1 - * @max 5.0 - * @increment 0.01 - * @decimal 3 - * @group VTOL Attitude Control - -PARAM_DEFINE_FLOAT(VT_TRANS_P2_DUR, 0.5f);*/ diff --git a/src/modules/vtol_att_control/tiltrotor_params.c b/src/modules/vtol_att_control/tiltrotor_params.c deleted file mode 100644 index 31a6d549c0cb..000000000000 --- a/src/modules/vtol_att_control/tiltrotor_params.c +++ /dev/null @@ -1,101 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file tiltrotor_params.c - * Parameters for vtol attitude controller. - * - * @author Roman Bapst - */ - -/** - * Position of tilt servo in mc mode - * - * @min 0.0 - * @max 1.0 - * @increment 0.01 - * @decimal 3 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_TILT_MC, 0.0f); - -/** - * Position of tilt servo in transition mode - * - * @min 0.0 - * @max 1.0 - * @increment 0.01 - * @decimal 3 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_TILT_TRANS, 0.3f); - -/** - * Position of tilt servo in fw mode - * - * @min 0.0 - * @max 1.0 - * @increment 0.01 - * @decimal 3 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_TILT_FW, 1.0f); - -/** - * Tilt actuator control value commanded when disarmed and during the first second after arming. - * - * This specific tilt during spin-up is necessary for some systems whose motors otherwise don't - * spin-up freely. - * - * @min 0.0 - * @max 1.0 - * @increment 0.01 - * @decimal 3 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_TILT_SPINUP, 0.0f); - -/** - * Duration of front transition phase 2 - * - * Time in seconds it should take for the rotors to rotate forward completely from the point - * when the plane has picked up enough airspeed and is ready to go into fixed wind mode. - * - * @unit s - * @min 0.1 - * @max 5.0 - * @increment 0.01 - * @decimal 3 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_TRANS_P2_DUR, 0.5f); diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c deleted file mode 100644 index 035426ac0767..000000000000 --- a/src/modules/vtol_att_control/vtol_att_control_params.c +++ /dev/null @@ -1,387 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file vtol_att_control_params.c - * Parameters for vtol attitude controller. - * - * @author Roman Bapst - * @author Sander Smeets - */ - -/** - * Idle speed of VTOL when in multicopter mode - * - * @unit us - * @min 900 - * @max 2000 - * @increment 1 - * @decimal 0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_IDLE_PWM_MC, 900); - -/** - * VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2) - * - * @value 0 Tailsitter - * @value 1 Tiltrotor - * @value 2 Standard - * @min 0 - * @max 2 - * @decimal 0 - * @reboot_required true - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_TYPE, 0); - -/** - * Lock control surfaces in hover - * - * If set to 1 the control surfaces are locked at the disarmed value in multicopter mode. - * - * @boolean - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK, 1); - -/** - * Duration of a front transition - * - * Time in seconds used for a transition - * - * @unit s - * @min 0.1 - * @max 20.00 - * @increment 1 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_F_TRANS_DUR, 5.0f); - -/** - * Duration of a back transition - * - * Time in seconds used for a back transition - * - * @unit s - * @min 0.1 - * @max 20.00 - * @increment 1 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_B_TRANS_DUR, 4.0f); - -/** - * Target throttle value for the transition to fixed wing flight. - * - * standard vtol: pusher - * - * tailsitter, tiltrotor: main throttle - * - * @min 0.0 - * @max 1.0 - * @increment 0.01 - * @decimal 3 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_F_TRANS_THR, 1.0f); - -/** - * Target throttle value for the transition to hover flight. - * - * standard vtol: pusher - * - * tailsitter, tiltrotor: main throttle - * - * Note for standard vtol: - * For ESCs and mixers that support reverse thrust on low PWM values set this to a negative value to apply active breaking - * For ESCs that support thrust reversal with a control channel please set VT_B_REV_OUT and set this to a positive value to apply active breaking - * - * @min -1 - * @max 1 - * @increment 0.01 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_B_TRANS_THR, 0.0f); - -/** - * Approximate deceleration during back transition - * - * The approximate deceleration during a back transition in m/s/s - * Used to calculate back transition distance in mission mode. A lower value will make the VTOL transition further from the destination waypoint. - * For standard vtol and tiltrotors a controller is used to track this value during the transition. - * - * @unit m/s^2 - * @min 0.5 - * @max 10 - * @increment 0.1 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_B_DEC_MSS, 2.0f); - -/** - * Transition blending airspeed - * - * Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable. - * - * @unit m/s - * @min 0.00 - * @max 30.00 - * @increment 1 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_ARSP_BLEND, 8.0f); - -/** - * Transition airspeed - * - * Airspeed at which we can switch to fw mode - * - * @unit m/s - * @min 0.00 - * @max 30.00 - * @increment 1 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_ARSP_TRANS, 10.0f); - -/** - * Front transition timeout - * - * Time in seconds after which transition will be cancelled. Disabled if set to 0. - * - * @unit s - * @min 0.1 - * @max 30.00 - * @increment 1 - * @decimal 2 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_TRANS_TIMEOUT, 15.0f); - -/** - * Front transition minimum time - * - * Minimum time in seconds for front transition. - * - * @unit s - * @min 0.0 - * @max 20.0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_TRANS_MIN_TM, 2.0f); - -/** - * QuadChute Altitude - * - * Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude - * the vehicle will transition back to MC mode and enter failsafe RTL - * @min 0.0 - * @max 200.0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_FW_MIN_ALT, 0.0f); - -/** - * Adaptive QuadChute - * - * Maximum negative altitude error for fixed wing flight. If the altitude drops below this value below the altitude setpoint - * the vehicle will transition back to MC mode and enter failsafe RTL. - * @min 0.0 - * @max 200.0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_FW_ALT_ERR, 0.0f); - -/** - * QuadChute Max Pitch - * - * Maximum pitch angle before QuadChute engages - * Above this the vehicle will transition back to MC mode and enter failsafe RTL - * @min 0 - * @max 180 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_FW_QC_P, 0); - -/** - * QuadChute Max Roll - * - * Maximum roll angle before QuadChute engages - * Above this the vehicle will transition back to MC mode and enter failsafe RTL - * @min 0 - * @max 180 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_FW_QC_R, 0); - -/** - * Airspeed less front transition time (open loop) - * - * The duration of the front transition when there is no airspeed feedback available. - * - * @unit s - * @min 1.0 - * @max 30.0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_F_TR_OL_TM, 6.0f); - -/** - * The channel number of motors that must be turned off in fixed wing mode. - * - * @min 0 - * @max 12345678 - * @increment 1 - * @decimal 0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_FW_MOT_OFFID, 0); - -/** - * The channel number of motors which provide lift during hover. - * - * @min 0 - * @max 12345678 - * @increment 1 - * @decimal 0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_MOT_ID, 0); - -/** - * Differential thrust in forwards flight. - * - * Set to 1 to enable differential thrust in fixed-wing flight. - * - * @min 0 - * @max 1 - * @decimal 0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_FW_DIFTHR_EN, 0); - -/** - * Differential thrust scaling factor - * - * This factor specifies how the yaw input gets mapped to differential thrust in forwards flight. - * - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.1 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_FW_DIFTHR_SC, 0.1f); - -/** - * Backtransition deceleration setpoint to pitch feedforward gain. - * - * - * @unit rad s^2/m - * @min 0 - * @max 0.2 - * @decimal 1 - * @increment 0.01 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_B_DEC_FF, 0.f); - -/** - * Backtransition deceleration setpoint to pitch I gain. - * - * - * @unit rad s/m - * @min 0 - * @max 0.3 - * @decimal 1 - * @increment 0.05 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_B_DEC_I, 0.1f); - -/** - * Enable the usage of AUX outputs for hover motors. - * - * Set this parameter to true if the vehicle's hover motors are connected to the FMU (AUX) port. - * Not required for boards that only have a FMU, and no IO. - * Only applies for standard VTOL and tiltrotor. - * - * @boolean - * @group VTOL Attitude Control - */ -PARAM_DEFINE_INT32(VT_MC_ON_FMU, 0); - -/** - * Minimum pitch angle during hover. - * - * Minimum pitch angle during hover flight. If the desired pitch angle is is lower than this value - * then the fixed-wing forward actuation can be used to compensate for the missing thrust in forward direction - * (see VT_FW_TRHUST_EN) - * - * @min -10.0 - * @max 45.0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_PITCH_MIN, -5.0f); - -/** - * Minimum pitch angle during hover landing. - * - * Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). - * During landing it can be beneficial to allow lower minimum pitch angles as it can avoid the wings - * generating too much lift and preventing the vehicle from sinking at the desired rate. - * - * @min -10.0 - * @max 45.0 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_LND_PITCH_MIN, -5.0f); - -/** - * Spoiler setting while landing (hover) - * - * @unit norm - * @min -1 - * @max 1 - * @decimal 1 - * @increment 0.05 - * @group VTOL Attitude Control - */ -PARAM_DEFINE_FLOAT(VT_SPOILER_MC_LD, 0.f); diff --git a/validation/module_schema.yaml b/validation/module_schema.yaml index 64700568fb05..d5d42bd5f6a1 100644 --- a/validation/module_schema.yaml +++ b/validation/module_schema.yaml @@ -113,7 +113,7 @@ parameters: # Short description (one line) type: string required: true - maxlength: 70 + maxlength: 120 regex: '[^\n]+' long: # Long description (can be multiple lines) @@ -142,7 +142,7 @@ parameters: # (Extend this list as needed) type: string allowed: [ - '%', 'Hz', 'mAh', + '%', 'Hz', 'mAh', '1/s', 'rad', '%/rad', 'rad/s', 'rad/s^2', '%/rad/s', 'rad s^2/m','rad s/m', 'bit/s', 'B/s', 'deg', 'deg*1e7', 'deg/s', @@ -153,7 +153,8 @@ parameters: 'us', 'ms', 's', 'S', 'A/%', '(m/s^2)^2', 'm/m', 'tan(rad)^2', '(m/s)^2', 'm/rad', 'm/s^3/sqrt(Hz)', 'm/s/sqrt(Hz)', 's/(1000*PWM)', '%m/s', 'min', 'us/C', - 'N/(m/s)', 'Nm/(rad/s)', 'Nm', 'N', + '1/s/sqrt(Hz)', + 'N/(m/s)', 'Nm/(rad/s)', 'Nm', 'N', 'Nm/rad', 'RPM', 'normalized_thrust/s', 'normalized_thrust', 'norm', 'SD'] bit: # description of all bits for type bitmask.