Skip to content
Snippets Groups Projects
Commit 273988c1 authored by Beat Küng's avatar Beat Küng Committed by Daniel Agar
Browse files

SITL: move all models to unified rcS startup and remove old scripts

parent 5ebd0116
No related branches found
No related tags found
No related merge requests found
Showing
with 382 additions and 24 deletions
#!nsh
#
# @name 3DR Iris Quadrotor SITL (Optical Flow)
#
# @type Quadrotor Wide
#
sh /etc/init.d-posix/10016_iris
if [ $AUTOCNF == yes ]
then
param set EKF2_AID_MASK 2
param set EKF2_EV_DELAY 5
param set EKF2_EVP_NOISE 0.05
param set EKF2_EVA_NOISE 0.05
param set INAV_LIDAR_EST 1
param set INAV_W_XY_FLOW 1.0
param set INAV_W_XY_GPS_P 0.0
param set INAV_W_XY_GPS_V 0.0
param set INAV_W_Z_GPS_P 0.0
# LPE: Flow-only mode
param set LPE_FUSION 242
param set LPE_FAKE_ORIGIN 1
param set MPC_ALT_MODE 2
fi
mavlink stream -r 10 -s DISTANCE_SENSOR -u $udp_gcs_port_local
mavlink stream -r 10 -s VISION_POSITION_ESTIMATE -u $udp_gcs_port_local
#!nsh
#
# @name 3DR Iris Quadrotor SITL (irlock)
#
# @type Quadrotor Wide
#
sh /etc/init.d-posix/10016_iris
if [ $AUTOCNF == yes ]
then
# enable fusion of landing target velocity
param set LTEST_MODE 1
param set PLD_HACC_RAD 0.1
fi
#!nsh
#
# @name 3DR Iris Quadrotor SITL (rplidar)
#
# @type Quadrotor Wide
#
sh /etc/init.d-posix/10016_iris
if [ $AUTOCNF == yes ]
then
param set LPE_FUSION 242
fi
#!nsh
#
# @name 3DR Iris Quadrotor SITL (Vision)
#
# @type Quadrotor Wide
#
sh /etc/init.d-posix/1010_iris_opt_flow
if [ $AUTOCNF == yes ]
then
param set EKF2_AID_MASK 8
param set EKF2_EV_DELAY 5
fi
#!nsh
#
# @name Solo
#
# @type Quadrotor
#
sh /etc/init.d/rc.mc_defaults
if [ $AUTOCNF == yes ]
then
param set MC_PITCHRATE_P 0.15
param set MC_ROLLRATE_P 0.15
fi
set MIXER quad_x
#!nsh
#
# @name Hippocampus UUV
#
sh /etc/init.d/rc.mc_defaults
set MIXER uuv_quad_x
#!nsh
#
# @name Plane SITL
#
sh /etc/init.d/rc.fw_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 1
param set EKF2_ARSP_THR 8.0
param set EKF2_FUSE_BETA 1
param set EKF2_MAG_ACCLIM 0
param set EKF2_MAG_YAWLIM 0
param set FW_LND_ANG 8
param set FW_P_TC 0.5
param set FW_PR_FF 0.40
param set FW_PR_I 0.05
param set FW_PR_P 0.05
param set FW_R_TC 0.7
param set FW_RR_FF 0.20
param set FW_RR_I 0.02
param set FW_RR_P 0.22
param set FW_THR_IDLE 0.15
param set FW_W_EN 1
param set MIS_LTRMIN_ALT 30
param set MIS_TAKEOFF_ALT 30
param set NAV_ACC_RAD 15.0
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 50
param set RWTO_TKOFF 1
param set WEST_EN 1
fi
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
set MIXER custom
#!nsh
#
# @name Standard VTOL
#
# @type Standard VTOL
#
sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 22
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_MAX_DN 1.5
param set NAV_ACC_RAD 5.0
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 5
param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_TYPE 2
param set WEST_EN 1
fi
set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix
set MIXER custom
#!nsh
#
# @name Quadrotor + Tailsitter
#
# @type VTOL Quad Tailsitter
#
sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 20
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.15
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.05
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.8
param set NAV_ACC_RAD 5.0
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 1.5
param set VT_F_TRANS_THR 0.7
param set VT_MOT_COUNT 0
param set VT_TYPE 0
param set WEST_EN 1
fi
set MIXER_FILE etc/mixers-sitl/quad_x_vtol.main.mix
set MIXER custom
#!nsh
#
# @name VTOL Tiltrotor
#
# @type VTOL Tiltrotor
#
sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 21
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.15
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.05
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.8
param set NAV_ACC_RAD 5.0
param set NAV_LOITER_RAD 80
param set VT_F_TRANS_DUR 1.5
param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_TILT_FW 3.1415
param set VT_TILT_TRANS 1.2
param set VT_TYPE 1
param set WEST_EN 1
fi
set MIXER_FILE etc/mixers-sitl/tiltrotor_sitl.main.mix
set MIXER custom
#!nsh
#
# @name Rover
#
sh /etc/init.d/rc.ugv_defaults
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 10
param set GND_L1_DIST 5
param set GND_SP_CTRL_MODE 1
param set GND_SPEED_D 3
param set GND_SPEED_I 0.001
param set GND_SPEED_IMAX 0.125
param set GND_SPEED_P 0.25
param set GND_SPEED_THR_SC 1
param set GND_THR_CRUISE 0.3
param set GND_THR_IDLE 0
param set GND_THR_MAX 0.5
param set GND_THR_MIN 0
param set GND_SPEED_TRIM 4
param set GND_WR_D 1.2
param set GND_WR_I 0.9674
param set GND_WR_IMAX 0.1
param set GND_WR_P 2
param set MIS_LTRMIN_ALT 0.01
param set MIS_TAKEOFF_ALT 0.01
param set NAV_ACC_RAD 0.5
param set NAV_LOITER_RAD 2
param set CBRK_AIRSPD_CHK 162128
fi
set MIXER_FILE etc/mixers-sitl/rover_sitl.main.mix
......@@ -4,8 +4,9 @@
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
#
# Main SITL startup script
#
# check for ekf2 replay
if [ "$replay_mode" == "ekf2" ]
......@@ -21,6 +22,7 @@ set LOG_FILE bootlog.txt
set MAV_TYPE none
set MIXER none
set MIXER_AUX none
set MIXER_FILE none
set OUTPUT_MODE sim
set PWM_OUT none
set SDCARD_MIXERS_PATH etc/mixers
......@@ -34,6 +36,28 @@ if [ "$PX4_SIM_MODEL" == "shell" ]; then
set RUN_MINIMAL_SHELL yes
elif [ "$PX4_SIM_MODEL" == "iris" ]; then
set REQUESTED_AUTOSTART 10016
elif [ "$PX4_SIM_MODEL" == "iris_opt_flow" ]; then
set REQUESTED_AUTOSTART 1010
elif [ "$PX4_SIM_MODEL" == "iris_irlock" ]; then
set REQUESTED_AUTOSTART 1011
elif [ "$PX4_SIM_MODEL" == "iris_rplidar" ]; then
set REQUESTED_AUTOSTART 1012
elif [ "$PX4_SIM_MODEL" == "iris_vision" ]; then
set REQUESTED_AUTOSTART 1013
elif [ "$PX4_SIM_MODEL" == "solo" ]; then
set REQUESTED_AUTOSTART 1014
elif [ "$PX4_SIM_MODEL" == "hippocampus" ]; then
set REQUESTED_AUTOSTART 1020
elif [ "$PX4_SIM_MODEL" == "plane" ]; then
set REQUESTED_AUTOSTART 1030
elif [ "$PX4_SIM_MODEL" == "standard_vtol" ]; then
set REQUESTED_AUTOSTART 1040
elif [ "$PX4_SIM_MODEL" == "tailsitter" ]; then
set REQUESTED_AUTOSTART 1041
elif [ "$PX4_SIM_MODEL" == "tiltrotor" ]; then
set REQUESTED_AUTOSTART 1042
elif [ "$PX4_SIM_MODEL" == "rover" ]; then
set REQUESTED_AUTOSTART 1060
elif [ "$PX4_SIM_MODEL" == "typhoon_h480" ]; then
set REQUESTED_AUTOSTART 6011
else
......@@ -96,6 +120,8 @@ then
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set SENS_DPRES_OFF 0.001
param set CBRK_AIRSPD_CHK 0
param set COM_DISARM_LAND 3
param set COM_OBL_ACT 2
......@@ -114,6 +140,7 @@ then
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.2
param set MIS_TAKEOFF_ALT 2.5
param set MPC_ALT_MODE 0
param set MPC_HOLD_MAX_Z 2.0
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
......@@ -127,6 +154,11 @@ then
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SYS_RESTART_TYPE 2
# LPE: GPS only mode
param set LPE_FUSION 145
param set WEST_EN 0
fi
# Autostart ID
......@@ -153,6 +185,10 @@ sensors start
commander start
navigator start
if param compare WEST_EN 1
then
wind_estimator start
fi
if ! param compare MNT_MODE_IN -1
then
......@@ -166,6 +202,15 @@ then
camera_feedback start
fi
if [ ${VEHICLE_TYPE} == fw -o ${VEHICLE_TYPE} == vtol ]
then
if param compare CBRK_AIRSPD_CHK 0
then
measairspeedsim start
fi
fi
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.ugv_apps, and rc.vtol_apps.
......
......@@ -29,7 +29,3 @@ fw_pos_control_l1 start
#
land_detector start fixedwing
#
# Start Wind and Airspeed Scale Estimator.
#
#wind_estimator start
......@@ -55,7 +55,3 @@ fw_pos_control_l1 start
#
land_detector start vtol
#
# Start Wind and Airspeed Scale Estimator
#
#wind_estimator start
......@@ -486,7 +486,10 @@ else
#
# Start the standalone wind estimator.
#
wind_estimator start
if param compare WEST_EN 1
then
wind_estimator start
fi
#
# Start a thermal calibration if required.
......
......@@ -98,16 +98,10 @@ pushd "$rootfs" >/dev/null
# Do not exit on failure now from here on because we want the complete cleanup
set +e
# Use the new unified rcS for the supported models
# (All models will be transitioned over)
if [[ ($rcS_path == posix-configs/SITL/init/ekf2 || $rcS_path == posix-configs/SITL/init/lpe)
&& ($model == "iris" || $model == "typhoon_h480") ]]; then
echo "Using new unified rcS for $model"
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -t $src_path/test_data"
elif [[ ${model} == tests* ]]; then
if [[ ${model} == tests* ]]; then
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_test -s ${src_path}/${rcS_path}/${model} -t $src_path/test_data"
else
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_common -s ${src_path}/${rcS_path}/${model} -t $src_path/test_data"
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -t $src_path/test_data"
fi
echo SITL COMMAND: $sitl_command
......
#!/bin/bash
export PX4_SIM_MODEL="iris"
......@@ -14,7 +14,6 @@
<arg name="vehicle" default="iris"/>
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)"/>
<!-- gazebo configs -->
<arg name="gui" default="true"/>
......@@ -38,7 +37,6 @@
<arg name="world" value="$(arg world)"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="sdf" value="$(arg sdf)"/>
<arg name="rcS" value="$(arg rcS)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="interactive" value="$(arg interactive)"/>
<arg name="debug" value="$(arg debug)"/>
......
......@@ -33,7 +33,6 @@
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="rcS" value="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
<arg name="mavlink_udp_port" value="14561"/>
<arg name="ID" value="$(arg ID)"/>
</include>
......@@ -59,7 +58,6 @@
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="rcS" value="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
<arg name="mavlink_udp_port" value="14562"/>
<arg name="ID" value="$(arg ID)"/>
</include>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment