diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna b/ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna index 5fa839247e..b31256e6cf 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna @@ -10,6 +10,8 @@ PX4_SIMULATOR=${PX4_SIMULATOR:=gz} PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} PX4_SIM_MODEL=${PX4_SIM_MODEL:=rc_cessna} +param set-default SENS_EN_ARSPDSIM 1 + param set-default EKF2_MAG_ACCLIM 0 param set-default EKF2_MAG_YAWLIM 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index 5c3e5f7fca..84cc8bd430 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -11,6 +11,8 @@ PX4_SIMULATOR=${PX4_SIMULATOR:=gz} PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol} +param set-default SENS_EN_ARSPDSIM 1 + # TODO: Enable motor failure detection when the # VTOL no longer reports 0A for all ESCs in SITL param set-default FD_ACT_EN 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator index acc02a06d2..4e5f216735 100644 --- a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator +++ b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator @@ -80,7 +80,10 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th sensor_baro_sim start sensor_gps_sim start sensor_mag_sim start - sensor_airspeed_sim start + if param compare -s SENS_EN_ARSPDSIM 1 + then + sensor_airspeed_sim start + fi else echo "ERROR [init] gz_bridge failed to start" @@ -94,7 +97,10 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th sensor_baro_sim start sensor_gps_sim start sensor_mag_sim start - sensor_airspeed_sim start + if param compare -s SENS_EN_ARSPDSIM 1 + then + sensor_airspeed_sim start + fi else echo "ERROR [init] gz_bridge failed to start" @@ -109,7 +115,10 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th sensor_baro_sim start sensor_gps_sim start sensor_mag_sim start - sensor_airspeed_sim start + if param compare -s SENS_EN_ARSPDSIM 1 + then + sensor_airspeed_sim start + fi else echo "ERROR [init] gz_bridge failed to start" diff --git a/src/modules/simulation/sensor_airspeed_sim/parameters.c b/src/modules/simulation/sensor_airspeed_sim/parameters.c index 0b4d4d11cb..f462b69123 100644 --- a/src/modules/simulation/sensor_airspeed_sim/parameters.c +++ b/src/modules/simulation/sensor_airspeed_sim/parameters.c @@ -32,10 +32,13 @@ ****************************************************************************/ /** - * simulated GPS number of satellites used + * Enable simulated airspeed sensor instance * + * @reboot_required true * @min 0 - * @max 50 - * @group Simulator - */ -// PARAM_DEFINE_INT32(SIM_GPS_USED, 10); + * @max 1 + * @group Sensors + * @value 0 Disabled + * @value 1 Enabled + */ +PARAM_DEFINE_INT32(SENS_EN_ARSPDSIM, 0);