Optionally enable sensor simulations

This commit is contained in:
Jaeyoung Lim 2023-02-15 18:47:30 +01:00 committed by Daniel Agar
parent 3bdb42b6a7
commit 5676cc32bc
11 changed files with 109 additions and 12 deletions

View File

@ -12,6 +12,10 @@
PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadx}
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
# disable some checks to allow to fly:
# - with usb
param set-default CBRK_USB_CHK 197848

View File

@ -11,6 +11,11 @@
PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=airplane}
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
# disable some checks to allow to fly:
# - with usb
param set-default CBRK_USB_CHK 197848

View File

@ -11,6 +11,10 @@
PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=xvert}
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 0
param set-default VT_FW_DIFTHR_EN 1

View File

@ -13,6 +13,10 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4

View File

@ -13,6 +13,10 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_depth}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4

View File

@ -10,6 +10,9 @@ 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_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
param set-default EKF2_MAG_ACCLIM 0

View File

@ -11,6 +11,9 @@ 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_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
# TODO: Enable motor failure detection when the

View File

@ -10,9 +10,18 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0"
if simulator_sih start; then
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
else
echo "ERROR [init] simulator_sih failed to start"
@ -77,9 +86,18 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
# start gz bridge with pose arg.
if gz_bridge start -p "${model_pose}" -m "${PX4_GZ_MODEL}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
if param compare -s SENS_EN_ARSPDSIM 1
then
sensor_airspeed_sim start
@ -94,9 +112,18 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
# model name specificed, gz_bridge will attach to existing model
if gz_bridge start -n "${PX4_GZ_MODEL_NAME}" -w "${PX4_GZ_WORLD}"; then
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
if param compare -s SENS_EN_ARSPDSIM 1
then
sensor_airspeed_sim start
@ -112,9 +139,18 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
echo "WARN [init] PX4_GZ_MODEL_NAME or PX4_GZ_MODEL not set using PX4_SIM_MODEL."
if gz_bridge start -m "${PX4_SIM_MODEL#*gz_}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
if param compare -s SENS_EN_ARSPDSIM 1
then
sensor_airspeed_sim start

View File

@ -31,6 +31,18 @@
*
****************************************************************************/
/**
* Enable simulated barometer sensor instance
*
* @reboot_required true
* @min 0
* @max 1
* @group Sensors
* @value 0 Disabled
* @value 1 Enabled
*/
PARAM_DEFINE_INT32(SENS_EN_BAROSIM, 0);
/**
* simulated barometer pressure offset
*

View File

@ -30,6 +30,17 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* Enable simulated GPS sinstance
*
* @reboot_required true
* @min 0
* @max 1
* @group Sensors
* @value 0 Disabled
* @value 1 Enabled
*/
PARAM_DEFINE_INT32(SENS_EN_GPSSIM, 0);
/**
* simulated GPS number of satellites used

View File

@ -30,6 +30,17 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* Enable simulated magnetometer sensor instance
*
* @reboot_required true
* @min 0
* @max 1
* @group Sensors
* @value 0 Disabled
* @value 1 Enabled
*/
PARAM_DEFINE_INT32(SENS_EN_MAGSIM, 0);
/**
* simulated magnetometer X offset