From 64af812e8a12cbf9232b9b835aa20d06148124f6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 6 Jun 2019 09:32:18 +0200 Subject: [PATCH 1/4] omnibus rc.board_defaults: remove flash-based params transition logic --- boards/omnibus/f4sd/init/rc.board_defaults | 9 --------- 1 file changed, 9 deletions(-) diff --git a/boards/omnibus/f4sd/init/rc.board_defaults b/boards/omnibus/f4sd/init/rc.board_defaults index b0fa8f9057c5..daae85b4cb4a 100644 --- a/boards/omnibus/f4sd/init/rc.board_defaults +++ b/boards/omnibus/f4sd/init/rc.board_defaults @@ -4,15 +4,6 @@ #------------------------------------------------------------------------------ -# transition from params file to flash-based params (2018-12-20) -if [ -f $PARAM_FILE ] -then - param load $PARAM_FILE - param save - # create a backup - mv $PARAM_FILE ${PARAM_FILE}.bak - reboot -fi if [ $AUTOCNF = yes ] then From 89e4d83b6d5cc3882f8cb7763d363137860fc87b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 6 Jun 2019 09:33:48 +0200 Subject: [PATCH 2/4] SYS_MC_EST_GROUP: add q estimator only option and activate on omnibus --- ROMFS/px4fmu_common/init.d-posix/rcS | 4 +++- ROMFS/px4fmu_common/init.d/rc.mc_apps | 14 +++++++++++--- boards/omnibus/f4sd/init/rc.board_defaults | 8 +++++++- src/lib/systemlib/system_params.c | 3 +-- 4 files changed, 22 insertions(+), 7 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index 2191d48e42e0..f7afafc143da 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -65,7 +65,9 @@ fi # Use environment variable PX4_ESTIMATOR to choose estimator. -if [ "$PX4_ESTIMATOR" = "ekf2" ]; then +if [ "$PX4_ESTIMATOR" = "q" ]; then + param set SYS_MC_EST_GROUP 3 +elif [ "$PX4_ESTIMATOR" = "ekf2" ]; then param set SYS_MC_EST_GROUP 2 elif [ "$PX4_ESTIMATOR" = "lpe" ]; then param set SYS_MC_EST_GROUP 1 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps index 65329398ef32..5c652e6a644a 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_apps +++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps @@ -30,10 +30,18 @@ then fi else # - # EKF2 + # Q estimator (attitude estimation only) # - param set SYS_MC_EST_GROUP 2 - ekf2 start + if param compare SYS_MC_EST_GROUP 3 + then + attitude_estimator_q start + else + # + # EKF2 + # + param set SYS_MC_EST_GROUP 2 + ekf2 start + fi fi ############################################################################### diff --git a/boards/omnibus/f4sd/init/rc.board_defaults b/boards/omnibus/f4sd/init/rc.board_defaults index daae85b4cb4a..e26bffe55f88 100644 --- a/boards/omnibus/f4sd/init/rc.board_defaults +++ b/boards/omnibus/f4sd/init/rc.board_defaults @@ -4,6 +4,12 @@ #------------------------------------------------------------------------------ +# transition from LPE+Q to Q estimator (2019-06-05) +if param compare SYS_MC_EST_GROUP 1 +then + param set SYS_MC_EST_GROUP 3 +fi + if [ $AUTOCNF = yes ] then @@ -11,7 +17,7 @@ then param set CBRK_IO_SAFETY 22027 # use the Q attitude estimator, it works w/o mag or GPS. - param set SYS_MC_EST_GROUP 1 + param set SYS_MC_EST_GROUP 3 param set ATT_ACC_COMP 0 param set ATT_W_ACC 0.4000 param set ATT_W_GYRO_BIAS 0.0000 diff --git a/src/lib/systemlib/system_params.c b/src/lib/systemlib/system_params.c index f0041bef89fe..2b916f06e6fb 100644 --- a/src/lib/systemlib/system_params.c +++ b/src/lib/systemlib/system_params.c @@ -102,9 +102,8 @@ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2); * * @value 1 local_position_estimator, attitude_estimator_q (unsupported) * @value 2 ekf2 (recommended) + * @value 3 Q attitude estimator (no position) * - * @min 1 - * @max 2 * @reboot_required true * @group System */ From 493bcd8282177abc2d43ef94b7919995961a465e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 6 Jun 2019 09:34:34 +0200 Subject: [PATCH 3/4] aerofc rc.board_defaults: remove wrong parameter settings This was a regression. --- boards/intel/aerofc-v1/init/rc.board_defaults | 15 --------------- 1 file changed, 15 deletions(-) diff --git a/boards/intel/aerofc-v1/init/rc.board_defaults b/boards/intel/aerofc-v1/init/rc.board_defaults index 4890cb303bde..6a63205fa5f3 100644 --- a/boards/intel/aerofc-v1/init/rc.board_defaults +++ b/boards/intel/aerofc-v1/init/rc.board_defaults @@ -13,21 +13,6 @@ fi # other configurations. param set SYS_AUTOSTART 4070 -if [ $AUTOCNF = yes ] -then - # Disable safety switch by default - param set CBRK_IO_SAFETY 22027 - - # use the Q attitude estimator, it works w/o mag or GPS. - param set SYS_MC_EST_GROUP 1 - param set ATT_ACC_COMP 0 - param set ATT_W_ACC 0.4000 - param set ATT_W_GYRO_BIAS 0.0000 - - param set SYS_HAS_MAG 0 -fi - - set DATAMAN_OPT -i set LOGGER_ARGS "-m mavlink" set MIXER_AUX none From a54fc95b358f732fb0d04ff283e8586a0346a8cf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 6 Jun 2019 09:44:42 +0200 Subject: [PATCH 4/4] omnibus: enable dmesg buffer (3kb) without LPE running, we have about 17.6 kb more free RAM. --- boards/omnibus/f4sd/default.cmake | 1 + boards/omnibus/f4sd/src/board_config.h | 3 +++ 2 files changed, 4 insertions(+) diff --git a/boards/omnibus/f4sd/default.cmake b/boards/omnibus/f4sd/default.cmake index 479de8c79dd0..9271a1aca1b6 100644 --- a/boards/omnibus/f4sd/default.cmake +++ b/boards/omnibus/f4sd/default.cmake @@ -72,6 +72,7 @@ px4_add_board( SYSTEMCMDS #bl_update + dmesg config dumpfile esc_calib diff --git a/boards/omnibus/f4sd/src/board_config.h b/boards/omnibus/f4sd/src/board_config.h index 4fc43f6ee313..2e1dce831649 100644 --- a/boards/omnibus/f4sd/src/board_config.h +++ b/boards/omnibus/f4sd/src/board_config.h @@ -264,6 +264,9 @@ #define BOARD_HAS_ON_RESET 1 +#define BOARD_ENABLE_CONSOLE_BUFFER +#define BOARD_CONSOLE_BUFFER_SIZE (1024*3) + __BEGIN_DECLS /****************************************************************************************************