diff --git a/CONTRIBUTING.rst b/CONTRIBUTING.rst index eaa7097..5c9eb1c 100644 --- a/CONTRIBUTING.rst +++ b/CONTRIBUTING.rst @@ -70,6 +70,8 @@ Navigate into the location where you cloned *Parasect* and install the package w .. code:: console $ poetry install + $ poetry self add poetry-plugin-shell + $ poetry self add poetry-plugin-export You can now run an interactive Poetry shell, giving you access to the virtual environment. diff --git a/poetry.lock b/poetry.lock index 4bc2bf0..77ffe9b 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,4 +1,4 @@ -# This file is automatically @generated by Poetry 2.2.1 and should not be changed by hand. +# This file is automatically @generated by Poetry 2.3.2 and should not be changed by hand. [[package]] name = "alabaster" @@ -1310,6 +1310,7 @@ files = [ {file = "PyYAML-6.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:bf07ee2fef7014951eeb99f56f39c9bb4af143d8aa3c21b1677805985307da34"}, {file = "PyYAML-6.0.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:855fb52b0dc35af121542a76b9a84f8d1cd886ea97c84703eaa6d88e37a2ad28"}, {file = "PyYAML-6.0.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:40df9b996c2b73138957fe23a16a4f0ba614f4c0efce1e9406a184b6d07fa3a9"}, + {file = "PyYAML-6.0.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a08c6f0fe150303c1c6b71ebcd7213c2858041a7e01975da3a99aed1e7a378ef"}, {file = "PyYAML-6.0.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6c22bec3fbe2524cde73d7ada88f6566758a8f7227bfbf93a408a9d86bcc12a0"}, {file = "PyYAML-6.0.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8d4e9c88387b0f5c7d5f281e55304de64cf7f9c0021a3525bd3b1c542da3b0e4"}, {file = "PyYAML-6.0.1-cp312-cp312-win32.whl", hash = "sha256:d483d2cdf104e7c9fa60c544d92981f12ad66a457afae824d146093b8c294c54"}, @@ -1944,4 +1945,4 @@ tests-strict = ["pytest (==4.6.0) ; python_version < \"3.10.0\" and python_versi [metadata] lock-version = "2.1" python-versions = "^3.10" -content-hash = "69b4d25da33efd1305b23c76f5e452c2dd16c5a4bbf240f19bb7d89b722d60a3" +content-hash = "7bf1d85756f4dc5178ad8ca83aa6afb4e09c5f7cf69b1d767b7d2384e6118d85" diff --git a/pyproject.toml b/pyproject.toml index 192b35d..26836b8 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,6 +1,6 @@ [tool.poetry] name = "parasect" -version = "1.2.0" +version = "1.2.1-dev" description = "Utility for manipulating parameter sets for autopilots." authors = ["George Zogopoulos "] license = "MIT" diff --git a/src/parasect/_helpers.py b/src/parasect/_helpers.py index b04ca45..cab4a9b 100644 --- a/src/parasect/_helpers.py +++ b/src/parasect/_helpers.py @@ -198,6 +198,8 @@ class Formats(Enum): """Ardupilot-compatible file.""" apj = "apj" """File compatible with Ardupilot's apj tool.""" + mp = "mp" + """Ardupilot Mission Planner comma separated file with comments.""" ReservedOptions = Literal[ @@ -821,20 +823,6 @@ def build_param_from_qgc(row: list[str]) -> Parameter: return param -def build_param_from_ulog_params(row: list[str]) -> Parameter: - """Build a Parameter from an ulog_params printout entry.""" - param_name = row[0] - param_value: int | float - try: - param_value = int(row[1]) - except ValueError: - param_value = float(row[1]) - - param = Parameter(param_name, param_value) - - return param - - def build_param_from_mavproxy(item: Sequence) -> Parameter: """Convert a mavproxy parameter line to a parameter. @@ -951,45 +939,12 @@ def read_params_qgc(filepath: Path) -> ParameterList: raise (SyntaxError("Could not extract any parameter from file.")) return param_list + except UnicodeDecodeError as e: + raise SyntaxError(f"File encoding error - not a valid QGC parameter file: {e}") from e except SyntaxError as e: raise SyntaxError(f"File is not of QGC format:\n{e}") from e -@parser -def read_params_ulog_param(filepath: Path) -> ParameterList: - """Read and parse the outputs of the ulog_params program.""" - param_list = ParameterList() - - try: - with open(filepath) as csvfile: - param_reader = csv.reader(csvfile, delimiter=",") - for param_row in param_reader: # pragma: no branch - if param_row[0][0] == "#": # Skip comment lines - continue - # Check if line has exactly two elements - if len(param_row) != 2: - raise SyntaxError( - f"Invalid number of elements for ulog param decoder: {len(param_row)}" - ) - # Check if first element is a string - try: - float(param_row[0]) - raise SyntaxError( - "First row element must be a parameter name string" - ) - except ValueError: - pass - param = build_param_from_ulog_params(param_row) - param_list.add_param(param) - - if len(param_list.params) == 0: - raise (SyntaxError("Could not extract any parameter from file.")) - - return param_list - except SyntaxError as e: - raise SyntaxError(f"File is not of ulog format:\n{e}") from e - - def split_mavproxy_row(row: str) -> Sequence: """Split a line, assuming it is mavproxy syntax.""" params = row.split() @@ -1015,13 +970,41 @@ def split_mavproxy_row(row: str) -> Sequence: return params +def split_missionplanner_row(row: str) -> Sequence: + """Split a line, assuming it is MissionPlanner or ULOG (as its subset) syntax.""" + params = row.split(",", 1) + # Check if there's at least one comma (should have 2 parts) + if len(params) < 2: + raise SyntaxError("MP: Line must contain at least one comma separator.") + + # Check if first element is a string + try: + float(params[0]) + raise SyntaxError("MP: First row element must be a parameter name string.") + except ValueError: + pass + + value_reasoning = params[1].split("#", 1) + params[1] = value_reasoning[0].strip() + try: + float(params[1]) + except ValueError as e: + raise SyntaxError("MP: First row element must be a parameter name string.") from e + if len(value_reasoning) <= 1: + params.append("") + else: + params.append(value_reasoning[1].strip()) + + return params + + @parser def read_params_mavproxy(filepath: Path) -> ParameterList: """Read and parse the outputs of mavproxy.""" param_list = ParameterList() try: - with open(filepath) as f: + with open(filepath, encoding='utf-8') as f: for line in f: # pragma: no branch if line[0] == "#": # Skip comment lines continue @@ -1037,6 +1020,31 @@ def read_params_mavproxy(filepath: Path) -> ParameterList: raise SyntaxError(f"File is not of mavproxy format:\n{e}") from e +@parser +def read_params_missionplanner(filepath: Path) -> ParameterList: + """Read and parse the outputs of MissionPlanner or ULOG (as its subset).""" + param_list = ParameterList() + + try: + with open(filepath, encoding='utf-8') as f: + for line in f: # pragma: no branch + if line[0] == "#": # Skip comment lines + continue + # skip empty lines + if line.strip() == "": + continue + params = split_missionplanner_row(line) + param = build_param_from_mavproxy(params) + param_list.add_param(param) + + if len(param_list.params) == 0: + raise (SyntaxError("Could not extract any parameter from file.")) + + return param_list + except SyntaxError as e: + raise SyntaxError(f"File is not of MissionPlanner format:\n{e}") from e + + def read_params(filepath: Path) -> ParameterList: """Universal parameter reader.""" get_logger().debug(f"Attempting to read file {filepath}") diff --git a/src/parasect/build_lib.py b/src/parasect/build_lib.py index d910131..3d5fe13 100755 --- a/src/parasect/build_lib.py +++ b/src/parasect/build_lib.py @@ -642,30 +642,42 @@ def export_to_csv(self) -> Generator[str, None, None]: yield from self.retrieve_header_footer("footer", Formats.csv) def export_to_apm( - self, include_readonly: bool = False + self, include_readonly: bool = False, csv: bool = False, comments: bool = False ) -> Generator[str, None, None]: """Export as apm parameter file. INPUTS: include_readonly: flag to enable including @READONLY on a parameter. Necessary for apj tools, unsuitable for loading via a GCS. + csv: flag to use comma-separated format instead of tab-separated. + comments: flag to add parameter descriptions as comments after #. """ # Read header yield from self.retrieve_header_footer("header", Formats.apm) indentation = "" + separator = "," if csv else "\t" param_hashes = sorted(self.param_list.keys()) - for param_name in param_hashes: - param_name = self.param_list[param_name].name - param_value = self.param_list[param_name].get_pretty_value() - is_readonly = self.param_list[param_name].readonly + for param_hash in param_hashes: + param = self.param_list[param_hash] + param_name = param.name + param_value = param.get_pretty_value() + is_readonly = param.readonly + + # Build the parameter line + line = f"{indentation}{param_name}{separator}{param_value}" + + # Add readonly marker if needed if include_readonly and is_readonly: - readonly_string = "\t@READONLY" - else: - readonly_string = "" - - yield f"{indentation}{param_name}\t{param_value}{readonly_string}\n" + readonly_string = f"{separator}@READONLY" if csv else "\t@READONLY" + line += readonly_string + + # Add comment if requested and description is available + if comments and getattr(param, 'reasoning', None): + line += f" # {param.reasoning}" + + yield line + "\n" # Read footer yield from self.retrieve_header_footer("footer", Formats.apm) @@ -694,6 +706,8 @@ def export(self, format: Formats) -> Iterable[str]: return self.export_to_apm(include_readonly=False) elif format == Formats.apj: return self.export_to_apm(include_readonly=True) + elif format == Formats.mp: + return self.export_to_apm(include_readonly=False, csv=True, comments=True) else: raise ValueError(f"Output format {format} not supported.") @@ -734,6 +748,8 @@ def build_filename(format: Formats, meal: Meal) -> str: filename += ".hil" return filename elif format in (Formats.apm, Formats.apj): + return f"{meal.name}.parm" + elif format == Formats.mp: return f"{meal.name}.param" else: raise ValueError(f"Unsupported format {format}") diff --git a/tests/assets/ardupilot/mission_planner.param b/tests/assets/ardupilot/mission_planner.param new file mode 100644 index 0000000..75ee695 --- /dev/null +++ b/tests/assets/ardupilot/mission_planner.param @@ -0,0 +1,19 @@ +#ACRO_YAW_RATE,90 + +AHRS_ORIENTATION,25 # realflight + + +### Variant 1 - GPS module + Spoofing +AHRS_GPS_USE,1 +GPS1_TYPE,1 + + +### Variant 2 - LUA Script +#SCR_ENABLE,1 +AHRS_ORIG_LAT,37.090662 +#AHRS_ORIG_LON,-3.0745569 +#AHRS_ORIG_ALT,2736 + + +AHRS_OPTIONS,3 # вимкнути DCM fallback in VTOL and FW +#AHRS_OPTIONS,7 # don't disable AIRSPEED using EKF біт3 (в симуляторі результати гірше) diff --git a/tests/assets/ardupilot/sitl_copter_defaults.param b/tests/assets/ardupilot/sitl_copter_defaults.param new file mode 100644 index 0000000..4e22490 --- /dev/null +++ b/tests/assets/ardupilot/sitl_copter_defaults.param @@ -0,0 +1,1319 @@ +ACRO_BAL_PITCH,1 +ACRO_BAL_ROLL,1 +ACRO_OPTIONS,0 +ACRO_RP_EXPO,0.3 +ACRO_RP_RATE,360 +ACRO_RP_RATE_TC,0 +ACRO_THR_MID,0 +ACRO_TRAINER,2 +ACRO_Y_EXPO,0 +ACRO_Y_RATE,202.5 +ACRO_Y_RATE_TC,0 +ADSB_TYPE,0 +AHRS_COMP_BETA,0.1 +AHRS_EKF_TYPE,3 +AHRS_GPS_GAIN,1 +AHRS_GPS_MINSATS,6 +AHRS_GPS_USE,1 +AHRS_ORIENTATION,0 +AHRS_RP_P,0.2 +AHRS_TRIM_X,0 +AHRS_TRIM_Y,0 +AHRS_TRIM_Z,0 +AHRS_WIND_MAX,0 +AHRS_YAW_P,0.2 +ANGLE_MAX,3000 +ARMING_ACCTHRESH,0.75 +ARMING_CHECK,1 +ARMING_MIS_ITEMS,0 +ARMING_OPTIONS,0 +ARMING_RUDDER,2 +ARSPD_ENABLE,0 +ATC_ACCEL_P_MAX,110000 +ATC_ACCEL_R_MAX,110000 +ATC_ACCEL_Y_MAX,27000 +ATC_ANGLE_BOOST,1 +ATC_ANG_LIM_TC,1 +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_ANG_YAW_P,4.5 +ATC_INPUT_TC,0.15 +ATC_RATE_FF_ENAB,1 +ATC_RATE_P_MAX,0 +ATC_RATE_R_MAX,0 +ATC_RATE_Y_MAX,0 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_FF,0 +ATC_RAT_PIT_FLTD,20 +ATC_RAT_PIT_FLTE,0 +ATC_RAT_PIT_FLTT,20 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_IMAX,0.5 +ATC_RAT_PIT_P,0.135 +ATC_RAT_PIT_SMAX,0 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_FF,0 +ATC_RAT_RLL_FLTD,20 +ATC_RAT_RLL_FLTE,0 +ATC_RAT_RLL_FLTT,20 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_IMAX,0.5 +ATC_RAT_RLL_P,0.135 +ATC_RAT_RLL_SMAX,0 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_FF,0 +ATC_RAT_YAW_FLTD,0 +ATC_RAT_YAW_FLTE,2.5 +ATC_RAT_YAW_FLTT,20 +ATC_RAT_YAW_I,0.009 +ATC_RAT_YAW_IMAX,0.5 +ATC_RAT_YAW_P,0.09 +ATC_RAT_YAW_SMAX,0 +ATC_SLEW_YAW,6000 +ATC_THR_G_BOOST,0 +ATC_THR_MIX_MAN,0.1 +ATC_THR_MIX_MAX,0.5 +ATC_THR_MIX_MIN,0.1 +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,7 +AUTOTUNE_MIN_D,0.001 +AUTO_OPTIONS,0 +AVD_ENABLE,0 +AVOID_ACCEL_MAX,3 +AVOID_ALT_MIN,0 +AVOID_ANGLE_MAX,1000 +AVOID_BACKUP_DZ,0.1 +AVOID_BACKUP_SPD,0.75 +AVOID_BEHAVE,0 +AVOID_DIST_MAX,5 +AVOID_ENABLE,3 +AVOID_MARGIN,2 +BARO1_DEVID,65540 +BARO1_GND_PRESS,101079.796875 +BARO1_WCF_ENABLE,0 +BARO2_DEVID,65796 +BARO2_GND_PRESS,101080.945312 +BARO2_WCF_ENABLE,0 +BARO3_DEVID,0 +BARO3_GND_PRESS,0 +BARO3_WCF_ENABLE,0 +BARO_ALTERR_MAX,2000 +BARO_ALT_OFFSET,0 +BARO_EXT_BUS,-1 +BARO_FIELD_ELV,0 +BARO_FLTR_RNG,0 +BARO_GND_TEMP,0 +BARO_OPTIONS,0 +BARO_PRIMARY,0 +BARO_PROBE_EXT,0 +BATT2_MONITOR,0 +BATT3_MONITOR,0 +BATT4_MONITOR,0 +BATT5_MONITOR,0 +BATT6_MONITOR,0 +BATT7_MONITOR,0 +BATT8_MONITOR,0 +BATT9_MONITOR,0 +BATT_AMP_OFFSET,0 +BATT_AMP_PERVLT,17 +BATT_ARM_MAH,0 +BATT_ARM_VOLT,0 +BATT_CAPACITY,3300 +BATT_CRT_MAH,0 +BATT_CRT_VOLT,0 +BATT_CURR_PIN,12 +BATT_FS_CRT_ACT,0 +BATT_FS_LOW_ACT,0 +BATT_FS_VOLTSRC,0 +BATT_LOW_MAH,0 +BATT_LOW_TIMER,10 +BATT_LOW_VOLT,10.5 +BATT_MONITOR,4 +BATT_OPTIONS,0 +BATT_SERIAL_NUM,-1 +BATT_VLT_OFFSET,0 +BATT_VOLT_MULT,10.1 +BATT_VOLT_PIN,13 +BCN_TYPE,0 +BRD_BOOT_DELAY,0 +BRD_OPTIONS,0 +BRD_RTC_TYPES,1 +BRD_RTC_TZ_MIN,0 +BRD_SAFETYOPTION,3 +BRD_SAFETY_DEFLT,0 +BRD_SAFETY_MASK,16368 +BRD_SD_MISSION,0 +BRD_SERIAL_NUM,0 +BRD_VBUS_MIN,4.3 +BRD_VSERVO_MIN,0 +BTN_ENABLE,0 +CAM1_TYPE,0 +CAM2_TYPE,0 +CAM_AUTO_ONLY,0 +CAM_MAX_ROLL,0 +CAM_RC_TYPE,0 +CAN_D1_PROTOCOL,1 +CAN_D2_PROTOCOL,1 +CAN_LOGLEVEL,0 +CAN_P1_DRIVER,0 +CAN_P2_DRIVER,0 +CC_TYPE,0 +CHUTE_ENABLED,0 +CIRCLE_OPTIONS,1 +CIRCLE_RADIUS,1000 +CIRCLE_RATE,20 +COMPASS_AUTODEC,1 +COMPASS_AUTO_ROT,2 +COMPASS_CAL_FIT,16 +COMPASS_DEC,0 +COMPASS_DEV_ID,97539 +COMPASS_DEV_ID2,131874 +COMPASS_DEV_ID3,263178 +COMPASS_DEV_ID4,97283 +COMPASS_DEV_ID5,97795 +COMPASS_DEV_ID6,98051 +COMPASS_DEV_ID7,0 +COMPASS_DEV_ID8,0 +COMPASS_DIA2_X,1 +COMPASS_DIA2_Y,1 +COMPASS_DIA2_Z,1 +COMPASS_DIA3_X,1 +COMPASS_DIA3_Y,1 +COMPASS_DIA3_Z,1 +COMPASS_DIA_X,1 +COMPASS_DIA_Y,1 +COMPASS_DIA_Z,1 +COMPASS_ENABLE,1 +COMPASS_EXTERN2,0 +COMPASS_EXTERN3,0 +COMPASS_EXTERNAL,1 +COMPASS_FLTR_RNG,0 +COMPASS_LEARN,0 +COMPASS_MOT2_X,0 +COMPASS_MOT2_Y,0 +COMPASS_MOT2_Z,0 +COMPASS_MOT3_X,0 +COMPASS_MOT3_Y,0 +COMPASS_MOT3_Z,0 +COMPASS_MOTCT,0 +COMPASS_MOT_X,0 +COMPASS_MOT_Y,0 +COMPASS_MOT_Z,0 +COMPASS_ODI2_X,0 +COMPASS_ODI2_Y,0 +COMPASS_ODI2_Z,0 +COMPASS_ODI3_X,0 +COMPASS_ODI3_Y,0 +COMPASS_ODI3_Z,0 +COMPASS_ODI_X,0 +COMPASS_ODI_Y,0 +COMPASS_ODI_Z,0 +COMPASS_OFFS_MAX,1800 +COMPASS_OFS2_X,5 +COMPASS_OFS2_Y,13 +COMPASS_OFS2_Z,-18 +COMPASS_OFS3_X,5 +COMPASS_OFS3_Y,13 +COMPASS_OFS3_Z,-18 +COMPASS_OFS_X,5 +COMPASS_OFS_Y,13 +COMPASS_OFS_Z,-18 +COMPASS_OPTIONS,0 +COMPASS_ORIENT,0 +COMPASS_ORIENT2,0 +COMPASS_ORIENT3,0 +COMPASS_PMOT_EN,0 +COMPASS_PRIO1_ID,97539 +COMPASS_PRIO2_ID,131874 +COMPASS_PRIO3_ID,263178 +COMPASS_SCALE,1 +COMPASS_SCALE2,1 +COMPASS_SCALE3,1 +COMPASS_TYPEMASK,0 +COMPASS_USE,1 +COMPASS_USE2,1 +COMPASS_USE3,1 +CUST_ROT_ENABLE,0 +DEV_OPTIONS,0 +DID_ENABLE,0 +DISARM_DELAY,10 +EAHRS_TYPE,0 +EFI_TYPE,0 +EK2_ENABLE,0 +EK3_ABIAS_P_NSE,0.003 +EK3_ACC_BIAS_LIM,1 +EK3_ACC_P_NSE,0.35 +EK3_AFFINITY,0 +EK3_ALT_M_NSE,2 +EK3_BCN_DELAY,50 +EK3_BCN_I_GTE,500 +EK3_BCN_M_NSE,1 +EK3_BETA_MASK,0 +EK3_CHECK_SCALE,100 +EK3_DRAG_BCOEF_X,0 +EK3_DRAG_BCOEF_Y,0 +EK3_DRAG_MCOEF,0 +EK3_DRAG_M_NSE,0.5 +EK3_EAS_I_GATE,400 +EK3_EAS_M_NSE,1.4 +EK3_ENABLE,1 +EK3_ERR_THRESH,0.2 +EK3_FLOW_DELAY,10 +EK3_FLOW_I_GATE,300 +EK3_FLOW_M_NSE,0.25 +EK3_FLOW_USE,1 +EK3_GBIAS_P_NSE,0.001 +EK3_GLITCH_RAD,25 +EK3_GND_EFF_DZ,4 +EK3_GPS_CHECK,31 +EK3_GPS_VACC_MAX,0 +EK3_GSF_RST_MAX,2 +EK3_GSF_RUN_MASK,3 +EK3_GSF_USE_MASK,3 +EK3_GYRO_P_NSE,0.015 +EK3_HGT_DELAY,60 +EK3_HGT_I_GATE,500 +EK3_HRT_FILT,2 +EK3_IMU_MASK,3 +EK3_LOG_LEVEL,0 +EK3_MAGB_P_NSE,0.0001 +EK3_MAGE_P_NSE,0.001 +EK3_MAG_CAL,3 +EK3_MAG_EF_LIM,50 +EK3_MAG_I_GATE,300 +EK3_MAG_MASK,0 +EK3_MAG_M_NSE,0.05 +EK3_MAX_FLOW,2.5 +EK3_NOAID_M_NSE,10 +EK3_OGNM_TEST_SF,2 +EK3_OGN_HGT_MASK,0 +EK3_POSNE_M_NSE,0.5 +EK3_POS_I_GATE,500 +EK3_PRIMARY,0 +EK3_RNG_I_GATE,500 +EK3_RNG_M_NSE,0.5 +EK3_RNG_USE_HGT,-1 +EK3_RNG_USE_SPD,2 +EK3_SRC1_POSXY,3 +EK3_SRC1_POSZ,1 +EK3_SRC1_VELXY,3 +EK3_SRC1_VELZ,3 +EK3_SRC1_YAW,1 +EK3_SRC2_POSXY,0 +EK3_SRC2_POSZ,1 +EK3_SRC2_VELXY,0 +EK3_SRC2_VELZ,0 +EK3_SRC2_YAW,0 +EK3_SRC3_POSXY,0 +EK3_SRC3_POSZ,1 +EK3_SRC3_VELXY,0 +EK3_SRC3_VELZ,0 +EK3_SRC3_YAW,0 +EK3_SRC_OPTIONS,1 +EK3_TAU_OUTPUT,25 +EK3_TERR_GRAD,0.1 +EK3_VELD_M_NSE,0.5 +EK3_VELNE_M_NSE,0.3 +EK3_VEL_I_GATE,500 +EK3_VIS_VERR_MAX,0.9 +EK3_VIS_VERR_MIN,0.1 +EK3_WENC_VERR,0.1 +EK3_WIND_PSCALE,1 +EK3_WIND_P_NSE,0.2 +EK3_YAW_I_GATE,300 +EK3_YAW_M_NSE,0.5 +ESC_CALIBRATION,0 +ESC_TLM_MAV_OFS,0 +FENCE_ACTION,1 +FENCE_ALT_MAX,100 +FENCE_ALT_MIN,-10 +FENCE_ENABLE,0 +FENCE_MARGIN,2 +FENCE_RADIUS,150 +FENCE_TOTAL,0 +FENCE_TYPE,7 +FFT_ENABLE,0 +FHLD_BRAKE_RATE,8 +FHLD_FILT_HZ,5 +FHLD_FLOW_MAX,0.6 +FHLD_QUAL_MIN,10 +FHLD_XY_FILT_HZ,5 +FHLD_XY_I,0.3 +FHLD_XY_IMAX,3000 +FHLD_XY_P,0.2 +FLIGHT_OPTIONS,0 +FLOW_TYPE,0 +FLTMODE1,7 +FLTMODE2,9 +FLTMODE3,6 +FLTMODE4,3 +FLTMODE5,5 +FLTMODE6,0 +FLTMODE_CH,5 +FOLL_ENABLE,0 +FORMAT_VERSION,120 +FRAME_CLASS,1 +FRAME_TYPE,0 +FRSKY_DNLINK1_ID,20 +FRSKY_DNLINK2_ID,7 +FRSKY_DNLINK_ID,27 +FRSKY_OPTIONS,0 +FRSKY_UPLINK_ID,13 +FS_CRASH_CHECK,1 +FS_DR_ENABLE,2 +FS_DR_TIMEOUT,30 +FS_EKF_ACTION,1 +FS_EKF_THRESH,0.8 +FS_GCS_ENABLE,0 +FS_GCS_TIMEOUT,5 +FS_OPTIONS,16 +FS_THR_ENABLE,1 +FS_THR_VALUE,975 +FS_VIBE_ENABLE,1 +GCS_PID_MASK,0 +GEN_TYPE,0 +GND_EFFECT_COMP,1 +GPS1_CAN_OVRIDE,0 +GPS2_CAN_OVRIDE,0 +GPS_AUTO_CONFIG,1 +GPS_AUTO_SWITCH,1 +GPS_BLEND_MASK,5 +GPS_BLEND_TC,10 +GPS_CAN_NODEID1,0 +GPS_CAN_NODEID2,0 +GPS_COM_PORT,1 +GPS_COM_PORT2,1 +GPS_DELAY_MS,0 +GPS_DELAY_MS2,0 +GPS_DRV_OPTIONS,0 +GPS_GNSS_MODE,0 +GPS_GNSS_MODE2,0 +GPS_HDOP_GOOD,140 +GPS_INJECT_TO,127 +GPS_MB1_TYPE,0 +GPS_MB2_TYPE,0 +GPS_MIN_DGPS,100 +GPS_MIN_ELEV,-100 +GPS_NAVFILTER,8 +GPS_POS1_X,0 +GPS_POS1_Y,0 +GPS_POS1_Z,0 +GPS_POS2_X,0 +GPS_POS2_Y,0 +GPS_POS2_Z,0 +GPS_PRIMARY,0 +GPS_RATE_MS,200 +GPS_RATE_MS2,200 +GPS_RAW_DATA,0 +GPS_SAVE_CFG,2 +GPS_SBAS_MODE,2 +GPS_SBP_LOGMASK,-256 +GPS_TYPE,1 +GPS_TYPE2,0 +GRIP_ENABLE,0 +GUID_OPTIONS,0 +GUID_TIMEOUT,3 +INITIAL_MODE,0 +INS_ACC1_CALTEMP,-300 +INS_ACC2OFFS_X,0.001 +INS_ACC2OFFS_Y,0.001 +INS_ACC2OFFS_Z,0.001 +INS_ACC2SCAL_X,1.001 +INS_ACC2SCAL_Y,1.001 +INS_ACC2SCAL_Z,1.001 +INS_ACC2_CALTEMP,-300 +INS_ACC2_ID,2753036 +INS_ACC3OFFS_X,0 +INS_ACC3OFFS_Y,0 +INS_ACC3OFFS_Z,0 +INS_ACC3SCAL_X,1 +INS_ACC3SCAL_Y,1 +INS_ACC3SCAL_Z,1 +INS_ACC3_CALTEMP,-300 +INS_ACC3_ID,0 +INS_ACCEL_FILTER,20 +INS_ACCOFFS_X,0.001 +INS_ACCOFFS_Y,0.001 +INS_ACCOFFS_Z,0.001 +INS_ACCSCAL_X,1.001 +INS_ACCSCAL_Y,1.001 +INS_ACCSCAL_Z,1.001 +INS_ACC_BODYFIX,2 +INS_ACC_ID,2753028 +INS_ENABLE_MASK,127 +INS_FAST_SAMPLE,1 +INS_GYR1_CALTEMP,25.018318 +INS_GYR2OFFS_X,0 +INS_GYR2OFFS_Y,0 +INS_GYR2OFFS_Z,0 +INS_GYR2_CALTEMP,25.018318 +INS_GYR2_ID,2752780 +INS_GYR3OFFS_X,0 +INS_GYR3OFFS_Y,0 +INS_GYR3OFFS_Z,0 +INS_GYR3_CALTEMP,-300 +INS_GYR3_ID,0 +INS_GYROFFS_X,0 +INS_GYROFFS_Y,0 +INS_GYROFFS_Z,0 +INS_GYRO_FILTER,20 +INS_GYRO_RATE,0 +INS_GYR_CAL,1 +INS_GYR_ID,2752772 +INS_HNTC2_ENABLE,0 +INS_HNTCH_ENABLE,0 +INS_LOG_BAT_CNT,1024 +INS_LOG_BAT_LGCT,32 +INS_LOG_BAT_LGIN,20 +INS_LOG_BAT_MASK,0 +INS_LOG_BAT_OPT,0 +INS_POS1_X,0 +INS_POS1_Y,0 +INS_POS1_Z,0 +INS_POS2_X,0 +INS_POS2_Y,0 +INS_POS2_Z,0 +INS_POS3_X,0 +INS_POS3_Y,0 +INS_POS3_Z,0 +INS_STILL_THRESH,2.5 +INS_TCAL1_ENABLE,0 +INS_TCAL2_ENABLE,0 +INS_TCAL3_ENABLE,0 +INS_TCAL_OPTIONS,0 +INS_TRIM_OPTION,1 +INS_USE,1 +INS_USE2,1 +INS_USE3,1 +KDE_NPOLE,14 +LAND_ALT_LOW,1000 +LAND_REPOSITION,1 +LAND_SPEED,50 +LAND_SPEED_HIGH,0 +LGR_ENABLE,0 +LOG_BACKEND_TYPE,1 +LOG_BITMASK,176126 +LOG_BLK_RATEMAX,0 +LOG_DARM_RATEMAX,0 +LOG_DISARMED,0 +LOG_FILE_BUFSIZE,200 +LOG_FILE_DSRMROT,0 +LOG_FILE_MB_FREE,500 +LOG_FILE_RATEMAX,0 +LOG_FILE_TIMEOUT,5 +LOG_MAV_BUFSIZE,8 +LOG_MAV_RATEMAX,0 +LOG_REPLAY,0 +LOIT_ACC_MAX,500 +LOIT_ANG_MAX,0 +LOIT_BRK_ACCEL,250 +LOIT_BRK_DELAY,1 +LOIT_BRK_JERK,500 +LOIT_SPEED,1250 +MIS_OPTIONS,0 +MIS_RESTART,0 +MIS_TOTAL,0 +MNT1_TYPE,0 +MNT2_TYPE,0 +MOT_BAT_CURR_MAX,0 +MOT_BAT_CURR_TC,5 +MOT_BAT_IDX,0 +MOT_BAT_VOLT_MAX,12.8 +MOT_BAT_VOLT_MIN,9.6 +MOT_BOOST_SCALE,0 +MOT_HOVER_LEARN,2 +MOT_OPTIONS,0 +MOT_PWM_MAX,2000 +MOT_PWM_MIN,1000 +MOT_PWM_TYPE,0 +MOT_SAFE_DISARM,0 +MOT_SAFE_TIME,1 +MOT_SLEW_DN_TIME,0 +MOT_SLEW_UP_TIME,0 +MOT_SPIN_ARM,0.1 +MOT_SPIN_MAX,0.95 +MOT_SPIN_MIN,0.15 +MOT_SPOOL_TIME,0.5 +MOT_THST_EXPO,0.65 +MOT_THST_HOVER,0.39 +MOT_YAW_HEADROOM,200 +MSP_OPTIONS,0 +MSP_OSD_NCELLS,0 +NMEA_MSG_EN,3 +NMEA_RATE_MS,100 +NTF_BUZZ_ON_LVL,1 +NTF_BUZZ_PIN,-1 +NTF_BUZZ_TYPES,5 +NTF_BUZZ_VOLUME,100 +NTF_DISPLAY_TYPE,0 +NTF_LED_BRIGHT,3 +NTF_LED_LEN,1 +NTF_LED_OVERRIDE,0 +NTF_LED_TYPES,24775 +OA_TYPE,0 +OSD_TYPE,0 +PHLD_BRAKE_ANGLE,3000 +PHLD_BRAKE_RATE,8 +PILOT_ACCEL_Z,250 +PILOT_SPEED_DN,0 +PILOT_SPEED_UP,250 +PILOT_THR_BHV,0 +PILOT_THR_FILT,0 +PILOT_TKOFF_ALT,0 +PILOT_Y_EXPO,0 +PILOT_Y_RATE,202.5 +PILOT_Y_RATE_TC,0 +PLDP_DELAY,0 +PLDP_RNG_MIN,0 +PLDP_SPEED_DN,0 +PLDP_THRESH,0.9 +PLND_ENABLED,0 +PRX1_TYPE,0 +PRX2_TYPE,0 +PRX3_TYPE,0 +PRX_ALT_MIN,1 +PRX_FILT,0.25 +PRX_IGN_GND,0 +PRX_LOG_RAW,0 +PSC_ACCZ_D,0 +PSC_ACCZ_FF,0 +PSC_ACCZ_FLTD,0 +PSC_ACCZ_FLTE,20 +PSC_ACCZ_FLTT,0 +PSC_ACCZ_I,1 +PSC_ACCZ_IMAX,800 +PSC_ACCZ_P,0.5 +PSC_ACCZ_SMAX,0 +PSC_ANGLE_MAX,0 +PSC_JERK_XY,5 +PSC_JERK_Z,5 +PSC_POSXY_P,1 +PSC_POSZ_P,1 +PSC_VELXY_D,0.5 +PSC_VELXY_FF,0 +PSC_VELXY_FLTD,5 +PSC_VELXY_FLTE,5 +PSC_VELXY_I,1 +PSC_VELXY_IMAX,1000 +PSC_VELXY_P,2 +PSC_VELZ_D,0 +PSC_VELZ_FF,0 +PSC_VELZ_FLTD,5 +PSC_VELZ_FLTE,5 +PSC_VELZ_I,0 +PSC_VELZ_IMAX,1000 +PSC_VELZ_P,5 +RALLY_INCL_HOME,1 +RALLY_LIMIT_KM,0.3 +RALLY_TOTAL,0 +RC10_DZ,0 +RC10_MAX,1900 +RC10_MIN,1100 +RC10_OPTION,0 +RC10_REVERSED,0 +RC10_TRIM,1500 +RC11_DZ,0 +RC11_MAX,1900 +RC11_MIN,1100 +RC11_OPTION,0 +RC11_REVERSED,0 +RC11_TRIM,1500 +RC12_DZ,0 +RC12_MAX,1900 +RC12_MIN,1100 +RC12_OPTION,0 +RC12_REVERSED,0 +RC12_TRIM,1500 +RC13_DZ,0 +RC13_MAX,1900 +RC13_MIN,1100 +RC13_OPTION,0 +RC13_REVERSED,0 +RC13_TRIM,1500 +RC14_DZ,0 +RC14_MAX,1900 +RC14_MIN,1100 +RC14_OPTION,0 +RC14_REVERSED,0 +RC14_TRIM,1500 +RC15_DZ,0 +RC15_MAX,1900 +RC15_MIN,1100 +RC15_OPTION,0 +RC15_REVERSED,0 +RC15_TRIM,1500 +RC16_DZ,0 +RC16_MAX,1900 +RC16_MIN,1100 +RC16_OPTION,0 +RC16_REVERSED,0 +RC16_TRIM,1500 +RC1_DZ,20 +RC1_MAX,2000 +RC1_MIN,1000 +RC1_OPTION,0 +RC1_REVERSED,0 +RC1_TRIM,1500 +RC2_DZ,20 +RC2_MAX,2000 +RC2_MIN,1000 +RC2_OPTION,0 +RC2_REVERSED,0 +RC2_TRIM,1500 +RC3_DZ,30 +RC3_MAX,2000 +RC3_MIN,1000 +RC3_OPTION,0 +RC3_REVERSED,0 +RC3_TRIM,1500 +RC4_DZ,20 +RC4_MAX,2000 +RC4_MIN,1000 +RC4_OPTION,0 +RC4_REVERSED,0 +RC4_TRIM,1500 +RC5_DZ,0 +RC5_MAX,2000 +RC5_MIN,1000 +RC5_OPTION,0 +RC5_REVERSED,0 +RC5_TRIM,1500 +RC6_DZ,0 +RC6_MAX,2000 +RC6_MIN,1000 +RC6_OPTION,0 +RC6_REVERSED,0 +RC6_TRIM,1500 +RC7_DZ,0 +RC7_MAX,2000 +RC7_MIN,1000 +RC7_OPTION,7 +RC7_REVERSED,0 +RC7_TRIM,1500 +RC8_DZ,0 +RC8_MAX,2000 +RC8_MIN,1000 +RC8_OPTION,0 +RC8_REVERSED,0 +RC8_TRIM,1500 +RC9_DZ,0 +RC9_MAX,1900 +RC9_MIN,1100 +RC9_OPTION,0 +RC9_REVERSED,0 +RC9_TRIM,1500 +RCMAP_PITCH,2 +RCMAP_ROLL,1 +RCMAP_THROTTLE,3 +RCMAP_YAW,4 +RC_FS_TIMEOUT,1 +RC_OPTIONS,32 +RC_OVERRIDE_TIME,3 +RC_PROTOCOLS,1 +RC_SPEED,490 +RELAY_DEFAULT,0 +RELAY_PIN,13 +RELAY_PIN2,-1 +RELAY_PIN3,-1 +RELAY_PIN4,-1 +RELAY_PIN5,-1 +RELAY_PIN6,-1 +RNGFND1_TYPE,0 +RNGFND2_TYPE,0 +RNGFND3_TYPE,0 +RNGFND4_TYPE,0 +RNGFND5_TYPE,0 +RNGFND6_TYPE,0 +RNGFND7_TYPE,0 +RNGFND8_TYPE,0 +RNGFND9_TYPE,0 +RNGFNDA_TYPE,0 +RNGFND_FILT,0.5 +RPM1_TYPE,0 +RPM2_TYPE,0 +RSSI_TYPE,0 +RTL_ALT,1500 +RTL_ALT_FINAL,0 +RTL_ALT_TYPE,0 +RTL_CLIMB_MIN,0 +RTL_CONE_SLOPE,3 +RTL_LOIT_TIME,5000 +RTL_OPTIONS,0 +RTL_SPEED,0 +SCHED_DEBUG,0 +SCHED_LOOP_RATE,400 +SCHED_OPTIONS,0 +SCR_ENABLE,0 +SERIAL0_BAUD,115 +SERIAL0_PROTOCOL,2 +SERIAL1_BAUD,57 +SERIAL1_OPTIONS,0 +SERIAL1_PROTOCOL,2 +SERIAL2_BAUD,57 +SERIAL2_OPTIONS,0 +SERIAL2_PROTOCOL,2 +SERIAL3_BAUD,38 +SERIAL3_OPTIONS,0 +SERIAL3_PROTOCOL,5 +SERIAL4_BAUD,38 +SERIAL4_OPTIONS,0 +SERIAL4_PROTOCOL,5 +SERIAL5_BAUD,57 +SERIAL5_OPTIONS,0 +SERIAL5_PROTOCOL,-1 +SERIAL6_BAUD,57 +SERIAL6_OPTIONS,0 +SERIAL6_PROTOCOL,-1 +SERIAL7_BAUD,57 +SERIAL7_OPTIONS,0 +SERIAL7_PROTOCOL,-1 +SERIAL_PASS1,0 +SERIAL_PASS2,-1 +SERIAL_PASSTIMO,15 +SERVO10_FUNCTION,0 +SERVO10_MAX,1900 +SERVO10_MIN,1100 +SERVO10_REVERSED,0 +SERVO10_TRIM,1500 +SERVO11_FUNCTION,0 +SERVO11_MAX,1900 +SERVO11_MIN,1100 +SERVO11_REVERSED,0 +SERVO11_TRIM,1500 +SERVO12_FUNCTION,0 +SERVO12_MAX,1900 +SERVO12_MIN,1100 +SERVO12_REVERSED,0 +SERVO12_TRIM,1500 +SERVO13_FUNCTION,0 +SERVO13_MAX,1900 +SERVO13_MIN,1100 +SERVO13_REVERSED,0 +SERVO13_TRIM,1500 +SERVO14_FUNCTION,0 +SERVO14_MAX,1900 +SERVO14_MIN,1100 +SERVO14_REVERSED,0 +SERVO14_TRIM,1500 +SERVO15_FUNCTION,0 +SERVO15_MAX,1900 +SERVO15_MIN,1100 +SERVO15_REVERSED,0 +SERVO15_TRIM,1500 +SERVO16_FUNCTION,0 +SERVO16_MAX,1900 +SERVO16_MIN,1100 +SERVO16_REVERSED,0 +SERVO16_TRIM,1500 +SERVO1_FUNCTION,33 +SERVO1_MAX,1900 +SERVO1_MIN,1100 +SERVO1_REVERSED,0 +SERVO1_TRIM,1500 +SERVO2_FUNCTION,34 +SERVO2_MAX,1900 +SERVO2_MIN,1100 +SERVO2_REVERSED,0 +SERVO2_TRIM,1500 +SERVO3_FUNCTION,35 +SERVO3_MAX,1900 +SERVO3_MIN,1100 +SERVO3_REVERSED,0 +SERVO3_TRIM,1500 +SERVO4_FUNCTION,36 +SERVO4_MAX,1900 +SERVO4_MIN,1100 +SERVO4_REVERSED,0 +SERVO4_TRIM,1500 +SERVO5_FUNCTION,0 +SERVO5_MAX,1900 +SERVO5_MIN,1100 +SERVO5_REVERSED,0 +SERVO5_TRIM,1500 +SERVO6_FUNCTION,0 +SERVO6_MAX,1900 +SERVO6_MIN,1100 +SERVO6_REVERSED,0 +SERVO6_TRIM,1500 +SERVO7_FUNCTION,0 +SERVO7_MAX,1900 +SERVO7_MIN,1100 +SERVO7_REVERSED,0 +SERVO7_TRIM,1500 +SERVO8_FUNCTION,0 +SERVO8_MAX,1900 +SERVO8_MIN,1100 +SERVO8_REVERSED,0 +SERVO8_TRIM,1500 +SERVO9_FUNCTION,0 +SERVO9_MAX,1900 +SERVO9_MIN,1100 +SERVO9_REVERSED,0 +SERVO9_TRIM,1500 +SERVO_32_ENABLE,0 +SERVO_DSHOT_ESC,0 +SERVO_DSHOT_RATE,0 +SERVO_FTW_MASK,0 +SERVO_FTW_POLES,14 +SERVO_FTW_RVMASK,0 +SERVO_GPIO_MASK,0 +SERVO_RATE,50 +SERVO_ROB_POSMAX,4095 +SERVO_ROB_POSMIN,0 +SERVO_SBUS_RATE,50 +SERVO_VOLZ_MASK,0 +SID_AXIS,0 +SIMPLE,0 +SIM_ACC1_BIAS_X,0 +SIM_ACC1_BIAS_Y,0 +SIM_ACC1_BIAS_Z,0 +SIM_ACC1_RND,0 +SIM_ACC1_SCAL_X,0 +SIM_ACC1_SCAL_Y,0 +SIM_ACC1_SCAL_Z,0 +SIM_ACC2_BIAS_X,0 +SIM_ACC2_BIAS_Y,0 +SIM_ACC2_BIAS_Z,0 +SIM_ACC2_RND,0 +SIM_ACC2_SCAL_X,0 +SIM_ACC2_SCAL_Y,0 +SIM_ACC2_SCAL_Z,0 +SIM_ACC3_BIAS_X,0 +SIM_ACC3_BIAS_Y,0 +SIM_ACC3_BIAS_Z,0 +SIM_ACC3_RND,0 +SIM_ACC3_SCAL_X,0 +SIM_ACC3_SCAL_Y,0 +SIM_ACC3_SCAL_Z,0 +SIM_ACCEL1_FAIL,0 +SIM_ACCEL2_FAIL,0 +SIM_ACCEL3_FAIL,0 +SIM_ACC_FAIL_MSK,0 +SIM_ACC_FILE_RW,0 +SIM_ACC_TRIM_X,0 +SIM_ACC_TRIM_Y,0 +SIM_ACC_TRIM_Z,0 +SIM_ADSB_ALT,1000 +SIM_ADSB_COUNT,-1 +SIM_ADSB_RADIUS,10000 +SIM_ADSB_TX,0 +SIM_ARSPD2_FAIL,0 +SIM_ARSPD2_FAILP,0 +SIM_ARSPD2_OFS,2013 +SIM_ARSPD2_PITOT,0 +SIM_ARSPD2_RATIO,1.99 +SIM_ARSPD2_RND,2 +SIM_ARSPD2_SIGN,0 +SIM_ARSPD_FAIL,0 +SIM_ARSPD_FAILP,0 +SIM_ARSPD_OFS,2013 +SIM_ARSPD_PITOT,0 +SIM_ARSPD_RATIO,1.99 +SIM_ARSPD_RND,2 +SIM_ARSPD_SIGN,0 +SIM_BAR2_DELAY,0 +SIM_BAR2_DISABLE,0 +SIM_BAR2_DRIFT,0 +SIM_BAR2_FREEZE,0 +SIM_BAR2_GLITCH,0 +SIM_BAR2_RND,0.2 +SIM_BAR2_WCF_BAK,0 +SIM_BAR2_WCF_DN,0 +SIM_BAR2_WCF_FWD,0 +SIM_BAR2_WCF_LFT,0 +SIM_BAR2_WCF_RGT,0 +SIM_BAR2_WCF_UP,0 +SIM_BAR3_DELAY,0 +SIM_BAR3_DISABLE,0 +SIM_BAR3_DRIFT,0 +SIM_BAR3_FREEZE,0 +SIM_BAR3_GLITCH,0 +SIM_BAR3_RND,0.2 +SIM_BAR3_WCF_BAK,0 +SIM_BAR3_WCF_DN,0 +SIM_BAR3_WCF_FWD,0 +SIM_BAR3_WCF_LFT,0 +SIM_BAR3_WCF_RGT,0 +SIM_BAR3_WCF_UP,0 +SIM_BARO_COUNT,2 +SIM_BARO_DELAY,0 +SIM_BARO_DISABLE,0 +SIM_BARO_DRIFT,0 +SIM_BARO_FREEZE,0 +SIM_BARO_GLITCH,0 +SIM_BARO_RND,0 +SIM_BARO_WCF_BAK,0 +SIM_BARO_WCF_DN,0 +SIM_BARO_WCF_FWD,0 +SIM_BARO_WCF_LFT,0 +SIM_BARO_WCF_RGT,0 +SIM_BARO_WCF_UP,0 +SIM_BATT_CAP_AH,0 +SIM_BATT_VOLTAGE,12.6 +SIM_BAUDLIMIT_EN,0 +SIM_DRIFT_SPEED,0.05 +SIM_DRIFT_TIME,5 +SIM_EFI_TYPE,0 +SIM_ENGINE_FAIL,0 +SIM_ENGINE_MUL,1 +SIM_ESC_ARM_RPM,0 +SIM_ESC_TELEM,1 +SIM_FLOAT_EXCEPT,1 +SIM_FLOW_DELAY,0 +SIM_FLOW_ENABLE,0 +SIM_FLOW_POS_X,0 +SIM_FLOW_POS_Y,0 +SIM_FLOW_POS_Z,0 +SIM_FLOW_RATE,10 +SIM_FLOW_RND,0.05 +SIM_FTOWESC_ENA,0 +SIM_FTOWESC_POW,4095 +SIM_GND_BEHAV,-1 +SIM_GPS2_ACC,0.3 +SIM_GPS2_ALT_OFS,0 +SIM_GPS2_BYTELOS,0 +SIM_GPS2_DISABLE,1 +SIM_GPS2_DRFTALT,0 +SIM_GPS2_GLTCH_X,0 +SIM_GPS2_GLTCH_Y,0 +SIM_GPS2_GLTCH_Z,0 +SIM_GPS2_HDG,0 +SIM_GPS2_HZ,5 +SIM_GPS2_LAG_MS,100 +SIM_GPS2_LCKTIME,0 +SIM_GPS2_NOISE,0 +SIM_GPS2_NUMSATS,10 +SIM_GPS2_POS_X,0 +SIM_GPS2_POS_Y,0 +SIM_GPS2_POS_Z,0 +SIM_GPS2_TYPE,1 +SIM_GPS2_VERR_X,0 +SIM_GPS2_VERR_Y,0 +SIM_GPS2_VERR_Z,0 +SIM_GPS_ACC,0.3 +SIM_GPS_ALT_OFS,0 +SIM_GPS_BYTELOSS,0 +SIM_GPS_DISABLE,0 +SIM_GPS_DRIFTALT,0 +SIM_GPS_GLITCH_X,0 +SIM_GPS_GLITCH_Y,0 +SIM_GPS_GLITCH_Z,0 +SIM_GPS_HDG,0 +SIM_GPS_HZ,5 +SIM_GPS_LAG_MS,100 +SIM_GPS_LOCKTIME,0 +SIM_GPS_LOG_NUM,0 +SIM_GPS_NOISE,0 +SIM_GPS_NUMSATS,10 +SIM_GPS_POS_X,0 +SIM_GPS_POS_Y,0 +SIM_GPS_POS_Z,0 +SIM_GPS_TYPE,1 +SIM_GPS_VERR_X,0 +SIM_GPS_VERR_Y,0 +SIM_GPS_VERR_Z,0 +SIM_GRPE_ENABLE,0 +SIM_GRPE_PIN,-1 +SIM_GRPS_ENABLE,0 +SIM_GRPS_GRAB,2000 +SIM_GRPS_PIN,-1 +SIM_GRPS_RELEASE,1000 +SIM_GRPS_REVERSE,0 +SIM_GYR1_BIAS_X,0 +SIM_GYR1_BIAS_Y,0 +SIM_GYR1_BIAS_Z,0 +SIM_GYR1_RND,0 +SIM_GYR1_SCALE_X,0 +SIM_GYR1_SCALE_Y,0 +SIM_GYR1_SCALE_Z,0 +SIM_GYR2_BIAS_X,0 +SIM_GYR2_BIAS_Y,0 +SIM_GYR2_BIAS_Z,0 +SIM_GYR2_RND,0 +SIM_GYR2_SCALE_X,0 +SIM_GYR2_SCALE_Y,0 +SIM_GYR2_SCALE_Z,0 +SIM_GYR3_BIAS_X,0 +SIM_GYR3_BIAS_Y,0 +SIM_GYR3_BIAS_Z,0 +SIM_GYR3_RND,0 +SIM_GYR3_SCALE_X,0 +SIM_GYR3_SCALE_Y,0 +SIM_GYR3_SCALE_Z,0 +SIM_GYR_FAIL_MSK,0 +SIM_GYR_FILE_RW,0 +SIM_IE24_ENABLE,0 +SIM_IE24_ERROR,0 +SIM_IE24_STATE,-1 +SIM_IMUT1_ENABLE,0 +SIM_IMUT2_ENABLE,0 +SIM_IMUT3_ENABLE,0 +SIM_IMUT_END,45 +SIM_IMUT_FIXED,0 +SIM_IMUT_START,25 +SIM_IMUT_TCONST,300 +SIM_IMU_COUNT,2 +SIM_IMU_POS_X,0 +SIM_IMU_POS_Y,0 +SIM_IMU_POS_Z,0 +SIM_INIT_ALT_OFS,0 +SIM_INIT_LAT_OFS,0 +SIM_INIT_LON_OFS,0 +SIM_INS_THR_MIN,0.1 +SIM_JSON_MASTER,0 +SIM_LED_LAYOUT,0 +SIM_LOOP_DELAY,0 +SIM_MAG1_DEVID,97539 +SIM_MAG1_DIA_X,0 +SIM_MAG1_DIA_Y,0 +SIM_MAG1_DIA_Z,0 +SIM_MAG1_FAIL,0 +SIM_MAG1_ODI_X,0 +SIM_MAG1_ODI_Y,0 +SIM_MAG1_ODI_Z,0 +SIM_MAG1_OFS_X,5 +SIM_MAG1_OFS_Y,13 +SIM_MAG1_OFS_Z,-18 +SIM_MAG1_ORIENT,0 +SIM_MAG1_SCALING,1 +SIM_MAG2_DEVID,131874 +SIM_MAG2_DIA_X,0 +SIM_MAG2_DIA_Y,0 +SIM_MAG2_DIA_Z,0 +SIM_MAG2_FAIL,0 +SIM_MAG2_ODI_X,0 +SIM_MAG2_ODI_Y,0 +SIM_MAG2_ODI_Z,0 +SIM_MAG2_OFS_X,5 +SIM_MAG2_OFS_Y,13 +SIM_MAG2_OFS_Z,-18 +SIM_MAG2_ORIENT,0 +SIM_MAG2_SCALING,1 +SIM_MAG3_DEVID,263178 +SIM_MAG3_DIA_X,0 +SIM_MAG3_DIA_Y,0 +SIM_MAG3_DIA_Z,0 +SIM_MAG3_FAIL,0 +SIM_MAG3_ODI_X,0 +SIM_MAG3_ODI_Y,0 +SIM_MAG3_ODI_Z,0 +SIM_MAG3_OFS_X,5 +SIM_MAG3_OFS_Y,13 +SIM_MAG3_OFS_Z,-18 +SIM_MAG3_ORIENT,0 +SIM_MAG3_SCALING,1 +SIM_MAG4_DEVID,97283 +SIM_MAG5_DEVID,97795 +SIM_MAG6_DEVID,98051 +SIM_MAG7_DEVID,0 +SIM_MAG8_DEVID,0 +SIM_MAG_ALY_HGT,1 +SIM_MAG_ALY_X,0 +SIM_MAG_ALY_Y,0 +SIM_MAG_ALY_Z,0 +SIM_MAG_DELAY,0 +SIM_MAG_MOT_X,0 +SIM_MAG_MOT_Y,0 +SIM_MAG_MOT_Z,0 +SIM_MAG_RND,0 +SIM_ODOM_ENABLE,0 +SIM_OH_MASK,0 +SIM_OPOS_ALT,584 +SIM_OPOS_HDG,353 +SIM_OPOS_LAT,-35.363262 +SIM_OPOS_LNG,149.165237 +SIM_PARA_ENABLE,0 +SIM_PARA_PIN,-1 +SIM_PIN_MASK,0 +SIM_PLD_ALT_LMT,15 +SIM_PLD_DIST_LMT,10 +SIM_PLD_ENABLE,0 +SIM_PLD_HEIGHT,0 +SIM_PLD_LAT,0 +SIM_PLD_LON,0 +SIM_PLD_OPTIONS,0 +SIM_PLD_ORIENT,24 +SIM_PLD_RATE,100 +SIM_PLD_TYPE,0 +SIM_PLD_YAW,0 +SIM_RATE_HZ,1200 +SIM_RC_CHANCOUNT,16 +SIM_RC_FAIL,0 +SIM_RICH_CTRL,-1 +SIM_RICH_ENABLE,0 +SIM_SAFETY_STATE,2 +SIM_SERVO_SPEED,0.14 +SIM_SHIP_DSIZE,10 +SIM_SHIP_ENABLE,0 +SIM_SHIP_OFS_X,0 +SIM_SHIP_OFS_Y,0 +SIM_SHIP_OFS_Z,0 +SIM_SHIP_PSIZE,1000 +SIM_SHIP_SPEED,3 +SIM_SHIP_SYSID,17 +SIM_SHOVE_TIME,0 +SIM_SHOVE_X,0 +SIM_SHOVE_Y,0 +SIM_SHOVE_Z,0 +SIM_SONAR_GLITCH,0 +SIM_SONAR_POS_X,0 +SIM_SONAR_POS_Y,0 +SIM_SONAR_POS_Z,0 +SIM_SONAR_RND,0 +SIM_SONAR_ROT,25 +SIM_SONAR_SCALE,12.1212 +SIM_SPEEDUP,1 +SIM_SPR_ENABLE,0 +SIM_SPR_PUMP,-1 +SIM_SPR_SPIN,-1 +SIM_TA_ENABLE,1 +SIM_TEMP_BFACTOR,0 +SIM_TEMP_BRD_OFF,20 +SIM_TEMP_START,25 +SIM_TEMP_TCONST,30 +SIM_TERRAIN,1 +SIM_THML_SCENARI,0 +SIM_TIDE_DIR,0 +SIM_TIDE_SPEED,0 +SIM_TIME_JITTER,0 +SIM_TWIST_TIME,0 +SIM_TWIST_X,0 +SIM_TWIST_Y,0 +SIM_TWIST_Z,0 +SIM_UART_LOSS,0 +SIM_VIB_FREQ_X,0 +SIM_VIB_FREQ_Y,0 +SIM_VIB_FREQ_Z,0 +SIM_VIB_MOT_HMNC,1 +SIM_VIB_MOT_MASK,0 +SIM_VIB_MOT_MAX,0 +SIM_VIB_MOT_MULT,1 +SIM_VICON_FAIL,0 +SIM_VICON_GLIT_X,0 +SIM_VICON_GLIT_Y,0 +SIM_VICON_GLIT_Z,0 +SIM_VICON_POS_X,0 +SIM_VICON_POS_Y,0 +SIM_VICON_POS_Z,0 +SIM_VICON_TMASK,3 +SIM_VICON_VGLI_X,0 +SIM_VICON_VGLI_Y,0 +SIM_VICON_VGLI_Z,0 +SIM_VICON_YAW,0 +SIM_VICON_YAWERR,0 +SIM_WAVE_AMP,0.5 +SIM_WAVE_DIR,0 +SIM_WAVE_ENABLE,0 +SIM_WAVE_LENGTH,10 +SIM_WAVE_SPEED,0.5 +SIM_WIND_DIR,180 +SIM_WIND_DIR_Z,0 +SIM_WIND_SPD,0 +SIM_WIND_T,0 +SIM_WIND_TURB,0 +SIM_WIND_T_ALT,60 +SIM_WIND_T_COEF,0.01 +SIM_WOW_PIN,-1 +SPRAY_ENABLE,0 +SR0_ADSB,4 +SR0_EXTRA1,4 +SR0_EXTRA2,4 +SR0_EXTRA3,4 +SR0_EXT_STAT,4 +SR0_PARAMS,0 +SR0_POSITION,4 +SR0_RAW_CTRL,4 +SR0_RAW_SENS,4 +SR0_RC_CHAN,4 +SR1_ADSB,0 +SR1_EXTRA1,0 +SR1_EXTRA2,0 +SR1_EXTRA3,0 +SR1_EXT_STAT,0 +SR1_PARAMS,0 +SR1_POSITION,0 +SR1_RAW_CTRL,0 +SR1_RAW_SENS,0 +SR1_RC_CHAN,0 +SR2_ADSB,0 +SR2_EXTRA1,0 +SR2_EXTRA2,0 +SR2_EXTRA3,0 +SR2_EXT_STAT,0 +SR2_PARAMS,0 +SR2_POSITION,0 +SR2_RAW_CTRL,0 +SR2_RAW_SENS,0 +SR2_RC_CHAN,0 +SR3_ADSB,0 +SR3_EXTRA1,0 +SR3_EXTRA2,0 +SR3_EXTRA3,0 +SR3_EXT_STAT,0 +SR3_PARAMS,0 +SR3_POSITION,0 +SR3_RAW_CTRL,0 +SR3_RAW_SENS,0 +SR3_RC_CHAN,0 +SR4_ADSB,0 +SR4_EXTRA1,0 +SR4_EXTRA2,0 +SR4_EXTRA3,0 +SR4_EXT_STAT,0 +SR4_PARAMS,0 +SR4_POSITION,0 +SR4_RAW_CTRL,0 +SR4_RAW_SENS,0 +SR4_RC_CHAN,0 +SRTL_ACCURACY,2 +SRTL_OPTIONS,0 +SRTL_POINTS,300 +STAT_BOOTCNT,2 +STAT_FLTTIME,0 +STAT_RESET,232743578 +STAT_RUNTIME,91 +SUPER_SIMPLE,0 +SURFTRAK_MODE,1 +SURFTRAK_TC,1 +SYSID_ENFORCE,0 +SYSID_MYGCS,255 +SYSID_THISMAV,1 +TCAL_ENABLED,0 +TELEM_DELAY,0 +TEMP1_TYPE,0 +TEMP2_TYPE,0 +TEMP3_TYPE,0 +TEMP_LOG,0 +TERRAIN_ENABLE,1 +TERRAIN_MARGIN,0.05 +TERRAIN_OFS_MAX,30 +TERRAIN_OPTIONS,0 +TERRAIN_SPACING,100 +THROW_MOT_START,0 +THROW_NEXTMODE,18 +THROW_TYPE,0 +THR_DZ,100 +TKOFF_RPM_MAX,0 +TKOFF_RPM_MIN,0 +TKOFF_SLEW_TIME,2 +TKOFF_THR_MAX,0.9 +TUNE,0 +TUNE_MAX,0 +TUNE_MIN,0 +VISO_TYPE,0 +VTX_ENABLE,0 +WINCH_TYPE,0 +WPNAV_ACCEL,250 +WPNAV_ACCEL_C,0 +WPNAV_ACCEL_Z,100 +WPNAV_JERK,1 +WPNAV_RADIUS,200 +WPNAV_RFND_USE,1 +WPNAV_SPEED,1000 +WPNAV_SPEED_DN,150 +WPNAV_SPEED_UP,250 +WPNAV_TER_MARGIN,10 +WP_NAVALT_MIN,0 +WP_YAW_BEHAVIOR,2 +WVANE_ENABLE,0 +ZIGZ_AUTO_ENABLE,0 diff --git a/tests/test_build_lib.py b/tests/test_build_lib.py index 0f71e67..ff5c985 100644 --- a/tests/test_build_lib.py +++ b/tests/test_build_lib.py @@ -398,11 +398,16 @@ def test_px4af(self, build_meals): def test_apm(self, build_meals): """Test the apm format.""" name = build_lib.build_filename(_helpers.Formats.apm, build_meals["my_vtol_1"]) - assert Path(name).suffix == ".param" + assert Path(name).suffix == ".parm" def test_apj(self, build_meals): """Test the apm format.""" name = build_lib.build_filename(_helpers.Formats.apj, build_meals["my_vtol_1"]) + assert Path(name).suffix == ".parm" + + def test_mp(self, build_meals): + """Test the MissionPlanner format.""" + name = build_lib.build_filename(_helpers.Formats.mp, build_meals["my_vtol_1"]) assert Path(name).suffix == ".param" diff --git a/tests/test_helpers.py b/tests/test_helpers.py index 0dea489..58833b9 100644 --- a/tests/test_helpers.py +++ b/tests/test_helpers.py @@ -390,7 +390,7 @@ def test_ulog_param(self): assert parameter_list["BAT1_A_PER_V"].value == pytest.approx(36.364) def test_ulog_param_2(self, tmp_path): - """Verify that a ulog file with a number in the first position raises an exception.""" + """Verify that a MissionPlanner (ulog) file with a number in the first position raises an exception.""" path = tmp_path new_file = path / "edited.params" old_fp = open(utils.PX4_ULOG_PARAMS_FILE) @@ -401,10 +401,10 @@ def test_ulog_param_2(self, tmp_path): new_fp.writelines(old_lines[50:-1]) # Write the rest of the lines new_fp.close() with pytest.raises(SyntaxError) as exc_info: - _helpers.read_params_ulog_param(new_file) + _helpers.read_params_missionplanner(new_file) assert ( str(exc_info.value) - == "File is not of ulog format:\nFirst row element must be a parameter name string" + == "File is not of MissionPlanner format:\nMP: First row element must be a parameter name string." ) def test_ulog_param_empty(self, tmp_path): @@ -414,11 +414,11 @@ def test_ulog_param_empty(self, tmp_path): with open(new_file, "w") as new_fp: new_fp.writelines([]) # Insert empty file with pytest.raises(SyntaxError) as exc_info: - _helpers.read_params_ulog_param(new_file) + _helpers.read_params_missionplanner(new_file) print(exc_info.value) assert ( str(exc_info.value) - == "File is not of ulog format:\nCould not extract any parameter from file." + == "File is not of MissionPlanner format:\nCould not extract any parameter from file." ) def test_unknown_protocol(self, tmp_path): @@ -434,12 +434,56 @@ def test_unknown_protocol(self, tmp_path): assert str(exc_info.value) == "Could not recognize log protocol." +class TestArdupilotMissionPlannerParamReaders: + """Test the MissionPlanner and more modern Ardupilot parameter file decoders.""" + + def test_mavproxy(self): + """Test reading from a parameter file saved by MAVProxy.""" + parameter_list = _helpers.read_params(utils.ARDUPILOT_DEFAULT_PARAM) + assert parameter_list["ARMING_ACCTHRESH"].value == pytest.approx(0.75) + + def test_split_row(self): + """Test that a number as the first element throws an error.""" + row = "42,42 # Comment" + with pytest.raises(SyntaxError) as exc_info: + _helpers.split_missionplanner_row(row) + assert ( + str(exc_info.value) == "MP: First row element must be a parameter name string." + ) + + def test_split_row_2(self): + """Ensure all 3 elements are decoded.""" + row = "NAME, 42 # Batman" + result = _helpers.split_missionplanner_row(row) + expected = ("NAME", "42", "Batman") + assert all([a == b for a, b in zip(result, expected)]) # noqa: B905 + # Disabling qa because 'strict' keyword not supported before 3.10 + + def test_parse_failure(self): + """Ensure an exception is thrown if parsing fails.""" + with pytest.raises(SyntaxError) as exc_info: + _helpers.read_params_missionplanner(utils.PX4_GAZEBO_PARAMS) + assert "File is not of MissionPlanner format" in str(exc_info.value) + + + def test_cyrillic_content(self): + """Ensure that value types 2,4,6,9 are correctly read.""" + parameter_list = _helpers.read_params(utils.ARDUPILOT_MP_PARAM) + assert parameter_list["AHRS_OPTIONS"].value == 3 + assert parameter_list["AHRS_OPTIONS"].reasoning == "вимкнути DCM fallback in VTOL and FW" + assert parameter_list["AHRS_GPS_USE"].value == 1 + assert parameter_list["AHRS_ORIG_LAT"].value == pytest.approx(37.09066) + + assert "ACRO_YAW_RATE" not in parameter_list + assert "AHRS_ORIG_ALT" not in parameter_list + + class TestArdupilotParamReaders: """Test the various Ardupilot parameter file decoders.""" def test_mavproxy(self): """Test reading from a parameter file saved by MAVProxy.""" - parameter_list = _helpers.read_params(utils.ARDUPILOT_DEFAULT_PARAMS) + parameter_list = _helpers.read_params(utils.ARDUPILOT_DEFAULT_PARM) assert parameter_list["ARMING_ACCTHRESH"].value == pytest.approx(0.75) def test_mavproxy_empty(self, tmp_path): @@ -482,7 +526,7 @@ def test_parse_failure(self): def test_qgc_rare_types(self): """Ensure that value types 2,4,6,9 are correctly read.""" - parameter_list = _helpers.read_params(utils.ARDUPILOT_ODD_PARAM_VALUES_FILE) + parameter_list = _helpers.read_params(utils.ARDUPILOT_ODD_PARAMS_VALUES_FILE) assert parameter_list["ACRO_TRAINER"].value == 2 assert parameter_list["ANGLE_MAX"].value == 3000 assert parameter_list["ARMING_CHECK"].value == 8214 diff --git a/tests/utils.py b/tests/utils.py index 8e9e56b..f07b8e6 100644 --- a/tests/utils.py +++ b/tests/utils.py @@ -20,10 +20,12 @@ PX4_INPUT_FOLDER = Path(PX4_ASSETS_PATH) / "menu" PX4_ULOG_PARAMS_FILE = PX4_ASSETS_PATH / "6fcfa754-186b-41ae-90a4-8de386f712c3.params" -PX4_ASSETS_PATH = Path(path.dirname(path.abspath(__file__))) / "assets" / "ardupilot" -ARDUPILOT_INPUT_FOLDER = Path(PX4_ASSETS_PATH) / "menu" -ARDUPILOT_DEFAULT_PARAMS = Path(PX4_ASSETS_PATH) / "sitl_copter_defaults.parm" -ARDUPILOT_ODD_PARAM_VALUES_FILE = Path(PX4_ASSETS_PATH) / "black_20231221.params" +ARDUPILOT_ASSETS_PATH = Path(path.dirname(path.abspath(__file__))) / "assets" / "ardupilot" +ARDUPILOT_INPUT_FOLDER = Path(ARDUPILOT_ASSETS_PATH) / "menu" +ARDUPILOT_DEFAULT_PARM = Path(ARDUPILOT_ASSETS_PATH) / "sitl_copter_defaults.parm" +ARDUPILOT_DEFAULT_PARAM = Path(ARDUPILOT_ASSETS_PATH) / "sitl_copter_defaults.param" +ARDUPILOT_MP_PARAM = Path(ARDUPILOT_ASSETS_PATH) / "mission_planner.param" +ARDUPILOT_ODD_PARAMS_VALUES_FILE = Path(ARDUPILOT_ASSETS_PATH) / "black_20231221.params" @pytest.fixture(name="setup_generic") @@ -59,7 +61,7 @@ def fixture_setup_px4(): def fixture_setup_ardupilot(): """Set up the parasect paths for Ardupilot testing.""" os.environ["PARASECT_PATH"] = str(ARDUPILOT_INPUT_FOLDER) - os.environ["PARASECT_DEFAULTS"] = str(ARDUPILOT_DEFAULT_PARAMS) + os.environ["PARASECT_DEFAULTS"] = str(ARDUPILOT_DEFAULT_PARM) parasect._helpers.ConfigPaths().clear()