aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_common/init.d')
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery2
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris6
-rw-r--r--ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d35
-rw-r--r--ROMFS/px4fmu_common/init.d/11001_hexa_cox2
-rw-r--r--ROMFS/px4fmu_common/init.d/2100_mpx_easystar2
-rw-r--r--ROMFS/px4fmu_common/init.d/3031_phantom4
-rw-r--r--ROMFS/px4fmu_common/init.d/4008_ardrone25
-rw-r--r--ROMFS/px4fmu_common/init.d/4010_dji_f3302
-rw-r--r--ROMFS/px4fmu_common/init.d/4011_dji_f4502
-rw-r--r--ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb28
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart10
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_apps2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_defaults2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_apps1
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults9
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb14
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS123
18 files changed, 184 insertions, 89 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index fe85f7d35..c4be16943 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -20,7 +20,7 @@ then
param set MC_PITCHRATE_D 0.0025
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.28
- param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
fi
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index f11aa704e..084dff140 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -18,9 +18,9 @@ then
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.004
- param set MC_YAW_P 0.5
- param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.0
+ param set MC_YAW_P 2.5
+ param set MC_YAWRATE_P 0.25
+ param set MC_YAWRATE_I 0.25
param set MC_YAWRATE_D 0.0
param set BAT_V_SCALING 0.00989
diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
new file mode 100644
index 000000000..6179855f6
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
@@ -0,0 +1,35 @@
+#!nsh
+#
+# Steadidrone QU4D
+#
+# Thomas Gubler <thomasgubler@gmail.com>
+# Lorenz Meier <lm@inf.ethz.ch>
+#
+
+sh /etc/init.d/rc.mc_defaults
+
+if [ $DO_AUTOCONFIG == yes ]
+then
+ # TODO tune roll/pitch separately
+ param set MC_ROLL_P 7.0
+ param set MC_ROLLRATE_P 0.13
+ param set MC_ROLLRATE_I 0.0
+ param set MC_ROLLRATE_D 0.004
+ param set MC_PITCH_P 7.0
+ param set MC_PITCHRATE_P 0.13
+ param set MC_PITCHRATE_I 0.0
+ param set MC_PITCHRATE_D 0.004
+ param set MC_YAW_P 0.5
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+
+ param set BAT_N_CELLS 4
+fi
+
+set MIXER FMU_quad_w
+
+set PWM_MIN 1210
+set PWM_MAX 2100
+
+set PWM_OUTPUTS 1234
diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
index df2e609bc..daa04a4de 100644
--- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox
+++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
@@ -1,7 +1,5 @@
#!nsh
#
-# UNTESTED UNTESTED!
-#
# Generic 10" Hexa coaxial geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
diff --git a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
index db0e40fc2..3ab2ac3d1 100644
--- a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
+++ b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
@@ -5,4 +5,4 @@
sh /etc/init.d/rc.fw_defaults
-set MIXER easystar.mix
+set MIXER easystar
diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom
index 24372bddc..d05c3174f 100644
--- a/ROMFS/px4fmu_common/init.d/3031_phantom
+++ b/ROMFS/px4fmu_common/init.d/3031_phantom
@@ -37,3 +37,7 @@ then
fi
set MIXER FMU_Q
+
+# Provide ESC a constant 1000 us pulse
+set PWM_OUTPUTS 4
+set PWM_DISARMED 1000
diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone
index 14786f210..e6007db0e 100644
--- a/ROMFS/px4fmu_common/init.d/4008_ardrone
+++ b/ROMFS/px4fmu_common/init.d/4008_ardrone
@@ -14,19 +14,20 @@ sh /etc/init.d/rc.mc_defaults
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
- param set MC_ROLL_P 5.0
- param set MC_ROLLRATE_P 0.13
- param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.0
- param set MC_PITCH_P 5.0
- param set MC_PITCHRATE_P 0.13
- param set MC_PITCHRATE_I 0.0
- param set MC_PITCHRATE_D 0.0
- param set MC_YAW_P 1.0
- param set MC_YAWRATE_P 0.15
- param set MC_YAWRATE_I 0.0
+ param set MC_ROLL_P 6.0
+ param set MC_ROLLRATE_P 0.14
+ param set MC_ROLLRATE_I 0.1
+ param set MC_ROLLRATE_D 0.002
+ param set MC_PITCH_P 6.0
+ param set MC_PITCHRATE_P 0.14
+ param set MC_PITCHRATE_I 0.1
+ param set MC_PITCHRATE_D 0.002
+ param set MC_YAW_P 2.0
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.0
- param set MC_YAW_FF 0.15
+ param set MC_YAW_FF 0.8
+
param set BAT_V_SCALING 0.00838095238
fi
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330
index cd4480c3e..e6e2e19dc 100644
--- a/ROMFS/px4fmu_common/init.d/4010_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330
@@ -19,7 +19,7 @@ then
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
fi
diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450
index ac2ecc70a..3465b59cf 100644
--- a/ROMFS/px4fmu_common/init.d/4011_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450
@@ -20,7 +20,7 @@ then
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
fi
diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb
new file mode 100644
index 000000000..99ffd73a5
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb
@@ -0,0 +1,28 @@
+#!nsh
+#
+# Hobbyking Micro Integrated PCB Quadcopter
+# with SimonK ESC firmware and Mystery A1510 motors
+#
+# Thomas Gubler <thomasgubler@gmail.com>
+#
+echo "HK Micro PCB Quad"
+
+sh /etc/init.d/4001_quad_x
+
+if [ $DO_AUTOCONFIG == yes ]
+then
+ param set MC_ROLL_P 7.0
+ param set MC_ROLLRATE_P 0.1
+ param set MC_ROLLRATE_I 0.0
+ param set MC_ROLLRATE_D 0.003
+ param set MC_PITCH_P 7.0
+ param set MC_PITCHRATE_P 0.1
+ param set MC_PITCHRATE_I 0.0
+ param set MC_PITCHRATE_D 0.003
+ param set MC_YAW_P 2.8
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+fi
+
+set PWM_MIN 1200
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 3d0de950d..17541e680 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -141,6 +141,11 @@ then
sh /etc/init.d/4012_quad_x_can
fi
+if param compare SYS_AUTOSTART 4020
+then
+ sh /etc/init.d/4020_hk_micro_pcb
+fi
+
#
# Quad +
#
@@ -200,6 +205,11 @@ then
sh /etc/init.d/10016_3dr_iris
fi
+if param compare SYS_AUTOSTART 10017
+then
+ sh /etc/init.d/10017_steadidrone_qu4d
+fi
+
#
# Hexa Coaxial
#
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps
index 429abc5ec..9aca3fc5f 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps
@@ -6,7 +6,7 @@
#
# Start the attitude and position estimator
#
-fw_att_pos_estimator start
+ekf_att_pos_estimator start
#
# Start attitude controller
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
index 4cd73e23f..3a50fcf56 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
@@ -11,6 +11,4 @@ then
param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1
param set NAV_ACCEPT_RAD 50
- param set RC_SCALE_ROLL 1
- param set RC_SCALE_PITCH 1
fi \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index 3469d5f5f..25f31a7e0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -8,9 +8,9 @@ then
if ver hwcmp PX4FMU_V1
then
echo "Start sdlog2 at 50Hz"
- sdlog2 start -r 50 -a -b 8 -t
+ sdlog2 start -r 50 -a -b 4 -t
else
echo "Start sdlog2 at 200Hz"
- sdlog2 start -r 200 -a -b 16 -t
+ sdlog2 start -r 200 -a -b 22 -t
fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps
index ed3939757..268eb9bba 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps
@@ -5,6 +5,7 @@
#
attitude_estimator_ekf start
+#ekf_att_pos_estimator start
position_estimator_inav start
mc_att_control start
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index a8c6dc811..0df320f49 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -14,7 +14,7 @@ then
param set MC_PITCHRATE_D 0.003
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAW_FF 0.5
@@ -35,6 +35,13 @@ then
param set MPC_TILTMAX_AIR 45.0
param set MPC_TILTMAX_LND 15.0
param set MPC_LAND_SPEED 1.0
+
+ param set PE_VELNE_NOISE 0.5
+ param set PE_VELD_NOISE 0.7
+ param set PE_POSNE_NOISE 0.5
+ param set PE_POSD_NOISE 1.0
+
+ param set NAV_ACCEPT_RAD 2.0
fi
set PWM_RATE 400
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index b7b556945..1f8d8b862 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -3,16 +3,22 @@
# USB MAVLink start
#
-echo "Starting MAVLink on this USB console"
-
-mavlink start -r 10000 -d /dev/ttyACM0
+mavlink start -r 10000 -d /dev/ttyACM0 -x
# Enable a number of interesting streams we want via USB
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
-mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 10
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s GLOBAL_POSITION_SETPOINT_INT -r 20
+usleep 100000
# Exit shell to make it available to MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 5d76e4283..c95016ace 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -65,12 +65,12 @@ then
# Start CDC/ACM serial driver
#
sercon
-
+
#
# Start the ORB (first app to start)
#
uorb start
-
+
#
# Load parameters
#
@@ -79,7 +79,7 @@ then
then
set PARAM_FILE /fs/mtd_params
fi
-
+
param select $PARAM_FILE
if param load
then
@@ -87,21 +87,25 @@ then
else
echo "[init] ERROR: Params loading failed: $PARAM_FILE"
fi
-
+
#
# Start system state indicator
#
if rgbled start
then
- echo "[init] Using external RGB Led"
+ echo "[init] RGB Led"
else
if blinkm start
then
- echo "[init] Using blinkm"
+ echo "[init] BlinkM"
blinkm systemstate
fi
fi
-
+
+ if pca8574 start
+ then
+ fi
+
#
# Set default values
#
@@ -122,17 +126,21 @@ then
set LOAD_DEFAULT_APPS yes
set GPS yes
set GPS_FAKE no
-
+
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
#
if param compare SYS_AUTOCONFIG 1
then
+ # We can't be sure the defaults haven't changed, so
+ # if someone requests a re-configuration, we do it
+ # cleanly from scratch (except autostart / autoconfig)
+ param reset_nostart
set DO_AUTOCONFIG yes
else
set DO_AUTOCONFIG no
fi
-
+
#
# Set USE_IO flag
#
@@ -142,7 +150,7 @@ then
else
set USE_IO no
fi
-
+
#
# Set parameters and env variables for selected AUTOSTART
#
@@ -172,9 +180,9 @@ then
param set SYS_AUTOCONFIG 0
param save
fi
-
+
set IO_PRESENT no
-
+
if [ $USE_IO == yes ]
then
#
@@ -186,19 +194,19 @@ then
else
set IO_FILE /etc/extras/px4io-v1_default.bin
fi
-
+
if px4io checkcrc $IO_FILE
then
echo "[init] PX4IO CRC OK"
echo "PX4IO CRC OK" >> $LOG_FILE
-
+
set IO_PRESENT yes
else
echo "[init] Trying to update"
echo "PX4IO Trying to update" >> $LOG_FILE
-
+
tone_alarm MLL32CP8MB
-
+
if px4io forceupdate 14662 $IO_FILE
then
usleep 500000
@@ -207,7 +215,7 @@ then
echo "[init] PX4IO CRC OK, update successful"
echo "PX4IO CRC OK after updating" >> $LOG_FILE
tone_alarm MLL8CDE
-
+
set IO_PRESENT yes
else
echo "[init] ERROR: PX4IO update failed"
@@ -220,14 +228,14 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
if [ $IO_PRESENT == no ]
then
echo "[init] ERROR: PX4IO not found"
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
#
# Set default output if not set
#
@@ -246,7 +254,7 @@ then
# Need IO for output but it not present, disable output
set OUTPUT_MODE none
echo "[init] ERROR: PX4IO not found, disabling output"
-
+
# Avoid using ttyS0 for MAVLink on FMUv1
if ver hwcmp PX4FMU_V1
then
@@ -270,17 +278,17 @@ then
# Try to get an USB console
nshterm /dev/ttyACM0 &
-
+
#
# Start the Commander (needs to be this early for in-air-restarts)
#
commander start
-
+
#
# Start primary output
#
set TTYS1_BUSY no
-
+
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
if [ $OUTPUT_MODE != none ]
then
@@ -306,7 +314,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
then
echo "[init] Use FMU as primary output"
@@ -317,7 +325,7 @@ then
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
@@ -330,7 +338,7 @@ then
fi
fi
fi
-
+
if [ $OUTPUT_MODE == mkblctrl ]
then
echo "[init] Use MKBLCTRL as primary output"
@@ -343,7 +351,7 @@ then
then
set MKBLCTRL_ARG "-mkmode +"
fi
-
+
if mkblctrl $MKBLCTRL_ARG
then
echo "[init] MKBLCTRL started"
@@ -351,9 +359,9 @@ then
echo "[init] ERROR: MKBLCTRL start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
fi
-
+
if [ $OUTPUT_MODE == hil ]
then
echo "[init] Use HIL as primary output"
@@ -365,7 +373,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
-
+
#
# Start IO or FMU for RC PPM input if needed
#
@@ -392,7 +400,7 @@ then
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
tone_alarm $TUNE_OUT_ERROR
fi
-
+
if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
@@ -407,7 +415,7 @@ then
fi
fi
fi
-
+
#
# MAVLink
#
@@ -428,28 +436,17 @@ then
fi
mavlink start $MAVLINK_FLAGS
-
- #
- # Start the datamanager
- #
- dataman start
-
- #
- # Start the navigator
- #
- navigator start
-
+
#
# Sensors, Logging, GPS
#
sh /etc/init.d/rc.sensors
- if [ $HIL == no ]
- then
- echo "[init] Start logging"
- sh /etc/init.d/rc.logging
- fi
-
+ #
+ # Start logging in all modes, including HIL
+ #
+ sh /etc/init.d/rc.logging
+
if [ $GPS == yes ]
then
echo "[init] Start GPS"
@@ -459,7 +456,7 @@ then
gps start -f
else
gps start
- fi
+ fi
fi
#
@@ -476,24 +473,24 @@ then
if [ $VEHICLE_TYPE == fw ]
then
echo "[init] Vehicle type: FIXED WING"
-
+
if [ $MIXER == none ]
then
# Set default mixer for fixed wing if not defined
set MIXER FMU_AERT
fi
-
+
if [ $MAV_TYPE == none ]
then
# Use MAV_TYPE = 1 (fixed wing) if not defined
set MAV_TYPE 1
fi
-
+
param set MAV_TYPE $MAV_TYPE
-
+
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
-
+
# Start standard fixedwing apps
if [ $LOAD_DEFAULT_APPS == yes ]
then
@@ -541,7 +538,7 @@ then
set MAV_TYPE 14
fi
fi
-
+
# Still no MAV_TYPE found
if [ $MAV_TYPE == none ]
then
@@ -549,10 +546,10 @@ then
else
param set MAV_TYPE $MAV_TYPE
fi
-
+
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
-
+
# Start standard multicopter apps
if [ $LOAD_DEFAULT_APPS == yes ]
then
@@ -561,6 +558,16 @@ then
fi
#
+ # Start the datamanager
+ #
+ dataman start
+
+ #
+ # Start the navigator
+ #
+ navigator start
+
+ #
# Generic setup (autostart ID not found)
#
if [ $VEHICLE_TYPE == none ]