forked from Archive/PX4-Autopilot
Optionally enable airspeed sensor sim
Enable and disable sensor sim module with parameter
This commit is contained in:
parent
192764387d
commit
3f50bd051f
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue