From 9dd6bef7f9f43af8ea92c6b3efe3d2d7df3f1031 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 31 Mar 2021 10:50:21 +0200 Subject: [PATCH] autostart scripts: remove SYS_PARAM_VER With the airframe defaults there's no use for that anymore --- ROMFS/px4fmu_common/init.d-posix/rcS | 2 +- .../init.d/airframes/4053_holybro_kopis2 | 2 -- ROMFS/px4fmu_common/init.d/rcS | 24 ++----------------- src/lib/systemlib/system_params.c | 16 +------------ .../BlockLocalPositionEstimator.hpp | 2 -- src/modules/mavlink/mavlink_parameters.cpp | 1 - 6 files changed, 4 insertions(+), 43 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index ce0d816123..ee6b876ea0 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -98,7 +98,7 @@ then set AUTOCNF yes # Wipe out params except RC*, flight modes, total flight time, accel cal, gyro cal, next flight UUID - param reset_all SYS_AUTOSTART SYS_AUTOCONFIG RC* COM_FLTMODE* LND_FLIGHT_T_* TC_* CAL_ACC* CAL_GYRO* COM_FLIGHT_UUID + param reset_all SYS_AUTO* RC* COM_FLTMODE* LND_FLIGHT* TC_* CAL_ACC* CAL_GYRO* COM_FLIGHT* fi # multi-instance setup diff --git a/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 b/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 index 8a59452e79..41a287c4c3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 +++ b/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 @@ -16,8 +16,6 @@ set MIXER quad_x set PWM_OUT 1234 -set PARAM_DEFAULTS_VER 2 - param set-default BAT_N_CELLS 4 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 69c3c1947a..38af11804b 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -51,12 +51,6 @@ set STARTUP_TUNE 1 set USE_IO no set VEHICLE_TYPE none -# Airframe parameter versioning: airframe maintainers can set this in the -# airframe startup script, and then increase it by one whenever an airframe -# parameter is updated - it will ensure that these parameters will be updated -# when the firmware is flashed. -set PARAM_DEFAULTS_VER 1 - # # Mount the procfs. # @@ -171,12 +165,8 @@ else # if param greater SYS_AUTOCONFIG 0 then - if param compare SYS_AUTOCONFIG 1 - then - # Wipe out params except RC*, flight modes, total flight time, calibration parameters, next flight UUID - param reset_all SYS_AUTO* RC* COM_FLTMODE* LND_FLIGHT* TC_* CAL_ACC* CAL_GYRO* COM_FLIGHT* SYS_PARAM_VER - fi - + # Wipe out params except RC*, flight modes, total flight time, calibration parameters, next flight UUID + param reset_all SYS_AUTO* RC* COM_FLTMODE* LND_FLIGHT* TC_* CAL_ACC* CAL_GYRO* COM_FLIGHT* set AUTOCNF yes fi @@ -562,15 +552,6 @@ else fi fi - if ! param compare SYS_PARAM_VER ${PARAM_DEFAULTS_VER} - then - echo "Switched to different parameter version. Resetting parameters." - param set SYS_PARAM_VER ${PARAM_DEFAULTS_VER} - param set SYS_AUTOCONFIG 2 - param save - reboot - fi - # # End of autostart. # @@ -595,7 +576,6 @@ unset MIXER unset MIXER_AUX unset MIXER_FILE unset OUTPUT_MODE -unset PARAM_DEFAULTS_VER unset PARAM_FILE unset PWM_AUX_OUT unset PWM_AUX_RATE diff --git a/src/lib/systemlib/system_params.c b/src/lib/systemlib/system_params.c index b59a39abf0..263097da27 100644 --- a/src/lib/systemlib/system_params.c +++ b/src/lib/systemlib/system_params.c @@ -57,8 +57,7 @@ PARAM_DEFINE_INT32(SYS_AUTOSTART, 0); * RC* parameters are preserved. * * @value 0 Keep parameters - * @value 1 Reset parameters - * @value 2 Reload airframe parameters + * @value 1 Reset parameters to airframe defaults * @group System */ PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0); @@ -114,19 +113,6 @@ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2); */ PARAM_DEFINE_INT32(SYS_MC_EST_GROUP, 2); -/** - * Parameter version - * - * This is used internally only: an airframe configuration might set an expected - * parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup - * against SYS_PARAM_VER, and if they do not match, parameters from the airframe - * configuration are reloaded. - * - * @min 0 - * @group System - */ -PARAM_DEFINE_INT32(SYS_PARAM_VER, 1); - /** * Enable auto start of rate gyro thermal calibration at the next power up. * diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp index e238b0ccb6..597d0e8e22 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp @@ -401,8 +401,6 @@ private: DEFINE_PARAMETERS( - (ParamInt) _param_sys_autostart, /**< example parameter */ - // general parameters (ParamInt) _param_lpe_fusion, (ParamFloat) _param_lpe_vxy_pub, diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index 4c1366eeff..eb0a31e41e 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -309,7 +309,6 @@ MavlinkParametersManager::send() param_find("SENS_BOARD_Y_OFF"); param_find("SENS_BOARD_Z_OFF"); param_find("SENS_DPRES_OFF"); - param_find("SYS_PARAM_VER"); param_find("TRIG_MODE"); param_find("UAVCAN_ENABLE");