mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
rcS and autostart scripts cleanup, WIP
This commit is contained in:
@@ -1,8 +1,9 @@
|
|||||||
#!nsh
|
#!nsh
|
||||||
|
#
|
||||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
# Team Blacksheep Discovery Quadcopter
|
||||||
|
#
|
||||||
echo "[init] Team Blacksheep Discovery Quad"
|
# Maintainers: Simon Wilks <sjwilks@gmail.com>
|
||||||
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
|
|||||||
@@ -1,11 +1,9 @@
|
|||||||
#!nsh
|
#!nsh
|
||||||
|
#
|
||||||
|
# 3DR Iris Quadcopter
|
||||||
|
#
|
||||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
echo "[init] 3DR Iris Quad"
|
|
||||||
|
|
||||||
# Use generic wide arm quad X PWM as base
|
|
||||||
sh /etc/init.d/10001_quad_w
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
@@ -41,3 +39,8 @@ then
|
|||||||
param set MPC_Z_VEL_MAX 2
|
param set MPC_Z_VEL_MAX 2
|
||||||
param set MPC_Z_VEL_P 0.20
|
param set MPC_Z_VEL_P 0.20
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
set VEHICLE_TYPE mc
|
||||||
|
set FRAME_GEOMETRY quad_w
|
||||||
|
|
||||||
|
set PWM_RATE 400
|
||||||
|
|||||||
+5
-2
@@ -1,6 +1,9 @@
|
|||||||
#!nsh
|
#!nsh
|
||||||
|
#
|
||||||
echo "[init] PX4FMU v1, v2 with or without IO on HIL Quad"
|
# HIL Quadcopter X
|
||||||
|
#
|
||||||
|
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
@@ -1,105 +1,46 @@
|
|||||||
#!nsh
|
#!nsh
|
||||||
#
|
#
|
||||||
# USB HIL start
|
# HIL Quadcopter +
|
||||||
|
#
|
||||||
|
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
echo "[HIL] HILS quadrotor + starting.."
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
|
|
||||||
#
|
|
||||||
# Load default params for this platform
|
|
||||||
#
|
|
||||||
if param compare SYS_AUTOCONFIG 1
|
|
||||||
then
|
then
|
||||||
# Set all params here, then disable autoconfig
|
#
|
||||||
param set SYS_AUTOCONFIG 0
|
# Default parameters for this platform
|
||||||
|
#
|
||||||
|
param set MC_ATTRATE_P 0.12
|
||||||
|
param set MC_ATTRATE_I 0.0
|
||||||
|
param set MC_ATTRATE_D 0.004
|
||||||
|
param set MC_ATT_P 7.0
|
||||||
|
param set MC_ATT_I 0.0
|
||||||
|
param set MC_ATT_D 0.0
|
||||||
|
param set MC_YAWPOS_P 2.0
|
||||||
|
param set MC_YAWPOS_I 0.0
|
||||||
|
param set MC_YAWPOS_D 0.0
|
||||||
|
param set MC_YAWRATE_P 0.3
|
||||||
|
param set MC_YAWRATE_I 0.2
|
||||||
|
param set MC_YAWRATE_D 0.005
|
||||||
|
|
||||||
param set MC_ATTRATE_D 0.0
|
param set MPC_TILT_MAX 0.5
|
||||||
param set MC_ATTRATE_I 0.0
|
param set MPC_THR_MAX 0.8
|
||||||
param set MC_ATTRATE_P 0.05
|
param set MPC_THR_MIN 0.2
|
||||||
param set MC_ATT_D 0.0
|
param set MPC_XY_D 0
|
||||||
param set MC_ATT_I 0.0
|
param set MPC_XY_P 0.5
|
||||||
param set MC_ATT_P 3.0
|
param set MPC_XY_VEL_D 0
|
||||||
param set MC_YAWPOS_D 0.0
|
param set MPC_XY_VEL_I 0
|
||||||
param set MC_YAWPOS_I 0.0
|
param set MPC_XY_VEL_MAX 3
|
||||||
param set MC_YAWPOS_P 2.1
|
param set MPC_XY_VEL_P 0.2
|
||||||
param set MC_YAWRATE_D 0.0
|
param set MPC_Z_D 0
|
||||||
param set MC_YAWRATE_I 0.0
|
param set MPC_Z_P 1
|
||||||
param set MC_YAWRATE_P 0.05
|
param set MPC_Z_VEL_D 0
|
||||||
param set NAV_TAKEOFF_ALT 3.0
|
param set MPC_Z_VEL_I 0.1
|
||||||
param set MPC_TILT_MAX 0.5
|
param set MPC_Z_VEL_MAX 2
|
||||||
param set MPC_THR_MAX 0.5
|
param set MPC_Z_VEL_P 0.20
|
||||||
param set MPC_THR_MIN 0.1
|
|
||||||
param set MPC_XY_D 0
|
|
||||||
param set MPC_XY_P 0.5
|
|
||||||
param set MPC_XY_VEL_D 0
|
|
||||||
param set MPC_XY_VEL_I 0
|
|
||||||
param set MPC_XY_VEL_MAX 3
|
|
||||||
param set MPC_XY_VEL_P 0.2
|
|
||||||
param set MPC_Z_D 0
|
|
||||||
param set MPC_Z_P 1
|
|
||||||
param set MPC_Z_VEL_D 0
|
|
||||||
param set MPC_Z_VEL_I 0.1
|
|
||||||
param set MPC_Z_VEL_MAX 2
|
|
||||||
param set MPC_Z_VEL_P 0.20
|
|
||||||
|
|
||||||
param save
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Allow USB some time to come up
|
set HIL yes
|
||||||
sleep 1
|
|
||||||
# Tell MAVLink that this link is "fast"
|
|
||||||
mavlink start -b 230400 -d /dev/ttyACM0
|
|
||||||
|
|
||||||
# Create a fake HIL /dev/pwm_output interface
|
|
||||||
hil mode_pwm
|
|
||||||
|
|
||||||
#
|
|
||||||
# Force some key parameters to sane values
|
|
||||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
|
||||||
# see https://pixhawk.ethz.ch/mavlink/
|
|
||||||
#
|
|
||||||
param set MAV_TYPE 2
|
|
||||||
|
|
||||||
#
|
|
||||||
# Check if we got an IO
|
|
||||||
#
|
|
||||||
if px4io start
|
|
||||||
then
|
|
||||||
echo "IO started"
|
|
||||||
else
|
|
||||||
fmu mode_serial
|
|
||||||
echo "FMU started"
|
|
||||||
fi
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start the sensors (depends on orb, px4io)
|
|
||||||
#
|
|
||||||
sh /etc/init.d/rc.sensors
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start the attitude estimator (depends on orb)
|
|
||||||
#
|
|
||||||
att_pos_estimator_ekf start
|
|
||||||
|
|
||||||
#
|
|
||||||
# Load mixer and start controllers (depends on px4io)
|
|
||||||
#
|
|
||||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start position estimator
|
|
||||||
#
|
|
||||||
position_estimator_inav start
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start attitude control
|
|
||||||
#
|
|
||||||
multirotor_att_control start
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start position control
|
|
||||||
#
|
|
||||||
multirotor_pos_control start
|
|
||||||
|
|
||||||
echo "[HIL] setup done, running"
|
|
||||||
|
|
||||||
|
set VEHICLE_TYPE mc
|
||||||
|
set FRAME_GEOMETRY quad_+
|
||||||
|
|||||||
@@ -1,8 +1,9 @@
|
|||||||
#!nsh
|
#!nsh
|
||||||
|
#
|
||||||
|
# DJI Flame Wheel F330 Quadcopter
|
||||||
|
#
|
||||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
echo "[init] DJI F330"
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
|
|||||||
@@ -1,8 +1,9 @@
|
|||||||
#!nsh
|
#!nsh
|
||||||
|
#
|
||||||
|
# DJI Flame Wheel F450 Quadcopter
|
||||||
|
#
|
||||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
||||||
|
#
|
||||||
echo "[init] DJI F450"
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
|
|||||||
@@ -1,8 +1,9 @@
|
|||||||
#!nsh
|
#!nsh
|
||||||
|
#
|
||||||
|
# HobbyKing X550 Quadcopter
|
||||||
|
#
|
||||||
# Maintainers: Todd Stellanova <tstellanova@gmail.com>
|
# Maintainers: Todd Stellanova <tstellanova@gmail.com>
|
||||||
|
#
|
||||||
echo "[init] PX4FMU v1, v2 with or without IO on HobbyKing X550"
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
then
|
then
|
||||||
@@ -21,6 +22,8 @@ then
|
|||||||
param set MC_YAWRATE_P 0.08
|
param set MC_YAWRATE_P 0.08
|
||||||
param set MC_YAWRATE_I 0
|
param set MC_YAWRATE_I 0
|
||||||
param set MC_YAWRATE_D 0
|
param set MC_YAWRATE_D 0
|
||||||
|
|
||||||
|
# TODO add default MPC parameters
|
||||||
fi
|
fi
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
set VEHICLE_TYPE mc
|
||||||
|
|||||||
@@ -28,7 +28,7 @@ fi
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 1001
|
if param compare SYS_AUTOSTART 1001
|
||||||
then
|
then
|
||||||
sh /etc/init.d/1001_rc_quad.hil
|
sh /etc/init.d/1001_rc_quad_x.hil
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if param compare SYS_AUTOSTART 1002
|
if param compare SYS_AUTOSTART 1002
|
||||||
@@ -38,7 +38,7 @@ fi
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 1003
|
if param compare SYS_AUTOSTART 1003
|
||||||
then
|
then
|
||||||
#sh /etc/init.d/1003_rc_quad_+.hil
|
sh /etc/init.d/1003_rc_quad_+.hil
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if param compare SYS_AUTOSTART 1004
|
if param compare SYS_AUTOSTART 1004
|
||||||
|
|||||||
+108
-87
@@ -13,18 +13,31 @@ set logfile /fs/microsd/bootlog.txt
|
|||||||
#
|
#
|
||||||
# Try to mount the microSD card.
|
# Try to mount the microSD card.
|
||||||
#
|
#
|
||||||
echo "[init] looking for microSD..."
|
echo "[init] Looking for microSD..."
|
||||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||||
then
|
then
|
||||||
echo "[init] card mounted at /fs/microsd"
|
echo "[init] microSD card mounted at /fs/microsd"
|
||||||
# Start playing the startup tune
|
# Start playing the startup tune
|
||||||
tone_alarm start
|
tone_alarm start
|
||||||
else
|
else
|
||||||
echo "[init] no microSD card found"
|
echo "[init] No microSD card found"
|
||||||
# Play SOS
|
# Play SOS
|
||||||
tone_alarm error
|
tone_alarm error
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Set default values here, can be overriden in rc.txt from SD card
|
||||||
|
#
|
||||||
|
set HIL no
|
||||||
|
set VEHICLE_TYPE none
|
||||||
|
set FRAME_GEOMETRY none
|
||||||
|
set OUTPUT_MODE none
|
||||||
|
set VEHICLE_TYPE none
|
||||||
|
set PWM_RATE none
|
||||||
|
set PWM_DISARMED none
|
||||||
|
set PWM_MIN none
|
||||||
|
set PWM_MAX none
|
||||||
|
|
||||||
#
|
#
|
||||||
# Look for an init script on the microSD card.
|
# Look for an init script on the microSD card.
|
||||||
#
|
#
|
||||||
@@ -70,27 +83,18 @@ then
|
|||||||
uorb start
|
uorb start
|
||||||
|
|
||||||
#
|
#
|
||||||
# Load microSD params
|
# Load parameters
|
||||||
#
|
#
|
||||||
#if ramtron start
|
param select /fs/microsd/params
|
||||||
#then
|
if [ -f /fs/microsd/params ]
|
||||||
# param select /ramtron/params
|
then
|
||||||
# if [ -f /ramtron/params ]
|
if param load /fs/microsd/params
|
||||||
# then
|
|
||||||
# param load /ramtron/params
|
|
||||||
# fi
|
|
||||||
#else
|
|
||||||
param select /fs/microsd/params
|
|
||||||
if [ -f /fs/microsd/params ]
|
|
||||||
then
|
then
|
||||||
if param load /fs/microsd/params
|
echo "[init] Parameters loaded"
|
||||||
then
|
else
|
||||||
echo "[init] Parameters loaded"
|
echo "[init] Parameter file corrupt - ignoring"
|
||||||
else
|
|
||||||
echo "[init] Parameter file corrupt - ignoring"
|
|
||||||
fi
|
|
||||||
fi
|
fi
|
||||||
#fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start system state indicator
|
# Start system state indicator
|
||||||
@@ -105,12 +109,8 @@ then
|
|||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Use FMU PWM output by default
|
|
||||||
set OUTPUT_MODE fmu_pwm
|
|
||||||
set IO_PRESENT no
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Upgrade PX4IO firmware
|
# Check if PX4IO present and update firmware if needed
|
||||||
#
|
#
|
||||||
if [ -f /etc/extras/px4io-v2_default.bin ]
|
if [ -f /etc/extras/px4io-v2_default.bin ]
|
||||||
then
|
then
|
||||||
@@ -119,15 +119,14 @@ then
|
|||||||
set io_file /etc/extras/px4io-v1_default.bin
|
set io_file /etc/extras/px4io-v1_default.bin
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
set IO_PRESENT no
|
||||||
|
|
||||||
if px4io checkcrc $io_file
|
if px4io checkcrc $io_file
|
||||||
then
|
then
|
||||||
echo "[init] PX4IO CRC OK"
|
echo "[init] PX4IO CRC OK"
|
||||||
echo "PX4IO CRC OK" >> $logfile
|
echo "PX4IO CRC OK" >> $logfile
|
||||||
|
|
||||||
set IO_PRESENT yes
|
set IO_PRESENT yes
|
||||||
|
|
||||||
# If PX4IO present, use it as primary PWM output by default
|
|
||||||
set OUTPUT_MODE io_pwm
|
|
||||||
else
|
else
|
||||||
echo "[init] PX4IO CRC failure"
|
echo "[init] PX4IO CRC failure"
|
||||||
echo "PX4IO CRC failure" >> $logfile
|
echo "PX4IO CRC failure" >> $logfile
|
||||||
@@ -142,9 +141,6 @@ then
|
|||||||
tone_alarm MSPAA
|
tone_alarm MSPAA
|
||||||
|
|
||||||
set IO_PRESENT yes
|
set IO_PRESENT yes
|
||||||
|
|
||||||
# If PX4IO present, use it as primary PWM output by default
|
|
||||||
set OUTPUT_MODE io_pwm
|
|
||||||
else
|
else
|
||||||
echo "[init] PX4IO restart failed"
|
echo "[init] PX4IO restart failed"
|
||||||
echo "PX4IO restart failed" >> $logfile
|
echo "PX4IO restart failed" >> $logfile
|
||||||
@@ -165,15 +161,26 @@ then
|
|||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
set HIL no
|
#
|
||||||
set FRAME_TYPE none
|
# Set default output if it was not defined in rc.txt
|
||||||
set PWM_RATE none
|
#
|
||||||
set PWM_DISARMED none
|
if [ $OUTPUT_MODE == none ]
|
||||||
set PWM_MIN none
|
then
|
||||||
set PWM_MAX none
|
if [ $IO_PRESENT == yes ]
|
||||||
|
then
|
||||||
|
# If PX4IO present, use it as primary PWM output by default
|
||||||
|
set OUTPUT_MODE io_pwm
|
||||||
|
else
|
||||||
|
# Else use PX4FMU PWM output
|
||||||
|
set OUTPUT_MODE fmu_pwm
|
||||||
|
fi
|
||||||
|
fi
|
||||||
|
|
||||||
set EXIT_ON_END no
|
set EXIT_ON_END no
|
||||||
|
|
||||||
|
#
|
||||||
|
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
|
||||||
|
#
|
||||||
if param compare SYS_AUTOCONFIG 1
|
if param compare SYS_AUTOCONFIG 1
|
||||||
then
|
then
|
||||||
set DO_AUTOCONFIG yes
|
set DO_AUTOCONFIG yes
|
||||||
@@ -181,41 +188,35 @@ then
|
|||||||
set DO_AUTOCONFIG no
|
set DO_AUTOCONFIG no
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
|
||||||
# Start the Commander (needs to be this early for in-air-restarts)
|
|
||||||
#
|
|
||||||
commander start
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Set parameters and env variables for selected AUTOSTART
|
# Set parameters and env variables for selected AUTOSTART
|
||||||
#
|
#
|
||||||
sh /etc/init.d/rc.autostart
|
sh /etc/init.d/rc.autostart
|
||||||
|
|
||||||
# Custom configuration
|
|
||||||
if [ -f /fs/microsd/etc/rc.conf ]
|
|
||||||
then
|
|
||||||
sh /fs/microsd/etc/rc.conf
|
|
||||||
fi
|
|
||||||
|
|
||||||
if [ $HIL == yes ]
|
|
||||||
then
|
|
||||||
set OUTPUT_MODE hil
|
|
||||||
else
|
|
||||||
# Try to get an USB console if not in HIL mode
|
|
||||||
nshterm /dev/ttyACM0 &
|
|
||||||
fi
|
|
||||||
|
|
||||||
#
|
|
||||||
# If autoconfig parameter was set, reset it and save parameters
|
|
||||||
#
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
|
||||||
then
|
|
||||||
param set SYS_AUTOCONFIG 0
|
|
||||||
param save
|
|
||||||
fi
|
|
||||||
|
|
||||||
if [ $MODE == autostart ]
|
if [ $MODE == autostart ]
|
||||||
then
|
then
|
||||||
|
if [ $HIL == yes ]
|
||||||
|
then
|
||||||
|
set OUTPUT_MODE hil
|
||||||
|
else
|
||||||
|
# Try to get an USB console if not in HIL mode
|
||||||
|
nshterm /dev/ttyACM0 &
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# If autoconfig parameter was set, reset it and save parameters
|
||||||
|
#
|
||||||
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
|
then
|
||||||
|
param set SYS_AUTOCONFIG 0
|
||||||
|
param save
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start the Commander (needs to be this early for in-air-restarts)
|
||||||
|
#
|
||||||
|
commander start
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start primary output
|
# Start primary output
|
||||||
#
|
#
|
||||||
@@ -224,29 +225,47 @@ then
|
|||||||
echo "[init] Use PX4IO PWM as primary output"
|
echo "[init] Use PX4IO PWM as primary output"
|
||||||
if px4io start
|
if px4io start
|
||||||
then
|
then
|
||||||
echo "[init] PX4IO OK"
|
echo "[init] PX4IO started"
|
||||||
echo "PX4IO OK" >> $logfile
|
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
else
|
else
|
||||||
echo "[init] PX4IO start error"
|
echo "[init] PX4IO start error"
|
||||||
echo "PX4IO start error" >> $logfile
|
|
||||||
tone_alarm MNGGG
|
tone_alarm MNGGG
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
if [ $OUTPUT_MODE == fmu_pwm ]
|
if [ $OUTPUT_MODE == fmu_pwm ]
|
||||||
then
|
then
|
||||||
echo "[init] Use PX4FMU PWM as primary output"
|
echo "[init] Use PX4FMU PWM as primary output"
|
||||||
fmu mode_pwm
|
if fmu mode_pwm
|
||||||
|
then
|
||||||
|
echo "[init] PX4FMU PWM output started"
|
||||||
|
sh /etc/init.d/rc.io
|
||||||
|
else
|
||||||
|
echo "[init] PX4FMU PWM output start error"
|
||||||
|
tone_alarm MNGGG
|
||||||
|
fi
|
||||||
fi
|
fi
|
||||||
if [ $OUTPUT_MODE == mkblctrl ]
|
if [ $OUTPUT_MODE == mkblctrl ]
|
||||||
then
|
then
|
||||||
echo "[init] Use MKBLCTRL as primary output"
|
echo "[init] Use MKBLCTRL as primary output"
|
||||||
mkblctrl
|
if mkblctrl
|
||||||
|
then
|
||||||
|
echo "[init] MKBLCTRL started"
|
||||||
|
else
|
||||||
|
echo "[init] MKBLCTRL start error"
|
||||||
|
tone_alarm MNGGG
|
||||||
|
fi
|
||||||
|
|
||||||
fi
|
fi
|
||||||
if [ $OUTPUT_MODE == hil ]
|
if [ $OUTPUT_MODE == hil ]
|
||||||
then
|
then
|
||||||
echo "[init] Use HIL as primary output"
|
echo "[init] Use HIL as primary output"
|
||||||
hil mode_pwm
|
if hil mode_pwm
|
||||||
|
then
|
||||||
|
echo "[init] HIL output started"
|
||||||
|
else
|
||||||
|
echo "[init] HIL output error"
|
||||||
|
tone_alarm MNGGG
|
||||||
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -257,12 +276,10 @@ then
|
|||||||
echo "[init] Use PX4IO PWM as secondary output"
|
echo "[init] Use PX4IO PWM as secondary output"
|
||||||
if px4io start
|
if px4io start
|
||||||
then
|
then
|
||||||
echo "[init] PX4IO OK"
|
echo "[init] PX4IO started"
|
||||||
echo "PX4IO OK" >> $logfile
|
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
else
|
else
|
||||||
echo "[init] PX4IO start error"
|
echo "[init] PX4IO start error"
|
||||||
echo "PX4IO start error" >> $logfile
|
|
||||||
tone_alarm MNGGG
|
tone_alarm MNGGG
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
@@ -270,18 +287,24 @@ then
|
|||||||
#
|
#
|
||||||
# MAVLink
|
# MAVLink
|
||||||
#
|
#
|
||||||
if [ $OUTPUT_MODE == fmu_pwm -a hw_ver compare PX4FMU_V1 ]
|
if [ $HIL == yes ]
|
||||||
then
|
then
|
||||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as PWM output
|
mavlink start -b 230400 -d /dev/ttyACM0
|
||||||
mavlink start -d /dev/ttyS0
|
|
||||||
usleep 5000
|
usleep 5000
|
||||||
|
|
||||||
# Exit from nsh to free port for mavlink
|
|
||||||
set EXIT_ON_END yes
|
|
||||||
else
|
else
|
||||||
# Start MAVLink on default port: ttyS1
|
if [ $OUTPUT_MODE == fmu_pwm -a hw_ver compare PX4FMU_V1 ]
|
||||||
mavlink start
|
then
|
||||||
usleep 5000
|
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as PWM output
|
||||||
|
mavlink start -d /dev/ttyS0
|
||||||
|
usleep 5000
|
||||||
|
|
||||||
|
# Exit from nsh to free port for mavlink
|
||||||
|
set EXIT_ON_END yes
|
||||||
|
else
|
||||||
|
# Start MAVLink on default port: ttyS1
|
||||||
|
mavlink start
|
||||||
|
usleep 5000
|
||||||
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -294,10 +317,7 @@ then
|
|||||||
then
|
then
|
||||||
echo "[init] Start logging"
|
echo "[init] Start logging"
|
||||||
sh /etc/init.d/rc.logging
|
sh /etc/init.d/rc.logging
|
||||||
fi
|
|
||||||
|
|
||||||
if [ $HIL == no ]
|
|
||||||
then
|
|
||||||
echo "[init] Start GPS"
|
echo "[init] Start GPS"
|
||||||
gps start
|
gps start
|
||||||
fi
|
fi
|
||||||
@@ -336,6 +356,7 @@ then
|
|||||||
if [ $VEHICLE_TYPE == none ]
|
if [ $VEHICLE_TYPE == none ]
|
||||||
then
|
then
|
||||||
echo "[init] Vehicle type: GENERIC"
|
echo "[init] Vehicle type: GENERIC"
|
||||||
|
|
||||||
attitude_estimator_ekf start
|
attitude_estimator_ekf start
|
||||||
position_estimator_inav start
|
position_estimator_inav start
|
||||||
fi
|
fi
|
||||||
|
|||||||
Reference in New Issue
Block a user