Browse Source

mc_autotune_attitude_control: add new MC_AT_EN parameter to enable

- only enabled by default on boards that aren't memory constrained
master
Daniel Agar 3 years ago
parent
commit
9c15be22d6
  1. 2
      ROMFS/px4fmu_common/init.d-posix/rcS
  2. 6
      ROMFS/px4fmu_common/init.d/rc.mc_apps
  3. 6
      ROMFS/px4fmu_common/init.d/rc.vtol_apps
  4. 2
      platforms/nuttx/init/imxrt/rc.board_arch_defaults
  5. 2
      platforms/nuttx/init/stm32f7/rc.board_arch_defaults
  6. 2
      platforms/nuttx/init/stm32h7/rc.board_arch_defaults
  7. 8
      src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c

2
ROMFS/px4fmu_common/init.d-posix/rcS

@ -144,6 +144,8 @@ param set-default SENS_MAG_MODE 0 @@ -144,6 +144,8 @@ param set-default SENS_MAG_MODE 0
param set-default IMU_GYRO_FFT_EN 1
param set-default -s MC_AT_EN 1
# By default log from boot until first disarm.
param set-default SDLOG_MODE 1
# enable default, estimator replay and vision/avoidance logging profiles

6
ROMFS/px4fmu_common/init.d/rc.mc_apps

@ -73,7 +73,11 @@ mc_rate_control start @@ -73,7 +73,11 @@ mc_rate_control start
# Start Multicopter Attitude Controller.
#
mc_att_control start
mc_autotune_attitude_control start
if param greater -s MC_AT_EN 0
then
mc_autotune_attitude_control start
fi
#
# Start Multicopter Position Controller.

6
ROMFS/px4fmu_common/init.d/rc.vtol_apps

@ -24,7 +24,11 @@ mc_att_control start vtol @@ -24,7 +24,11 @@ mc_att_control start vtol
flight_mode_manager start
mc_pos_control start vtol
mc_hover_thrust_estimator start
mc_autotune_attitude_control start
if param greater -s MC_AT_EN 0
then
mc_autotune_attitude_control start
fi
fw_att_control start vtol
fw_pos_control_l1 start vtol

2
platforms/nuttx/init/imxrt/rc.board_arch_defaults

@ -3,4 +3,6 @@ @@ -3,4 +3,6 @@
# imxrt specific defaults
#------------------------------------------------------------------------------
param set-default -s MC_AT_EN 1
set LOGGER_BUF 32

2
platforms/nuttx/init/stm32f7/rc.board_arch_defaults

@ -11,6 +11,8 @@ param set-default SENS_MAG_MODE 1 @@ -11,6 +11,8 @@ param set-default SENS_MAG_MODE 1
param set-default -s IMU_GYRO_FFT_EN 1
param set-default -s MC_AT_EN 1
param set-default -s UAVCAN_ENABLE 2
set LOGGER_BUF 64

2
platforms/nuttx/init/stm32h7/rc.board_arch_defaults

@ -11,6 +11,8 @@ param set-default SENS_MAG_MODE 0 @@ -11,6 +11,8 @@ param set-default SENS_MAG_MODE 0
param set-default -s IMU_GYRO_FFT_EN 1
param set-default -s MC_AT_EN 1
param set-default -s UAVCAN_ENABLE 2
set LOGGER_BUF 64

8
src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control_params.c

@ -39,6 +39,14 @@ @@ -39,6 +39,14 @@
* @author Mathieu Bresciani <mathieu@auterion.com>
*/
/**
* Multicopter autotune module enable
*
* @boolean
* @group Autotune
*/
PARAM_DEFINE_INT32(MC_AT_EN, 0);
/**
* Start the autotuning sequence
*

Loading…
Cancel
Save