forked from Archive/PX4-Autopilot
NuttX shell scripts: replace operator == with =
- NuttX supports both versions - POSIX shell only supports '='
This commit is contained in:
parent
4c90d2c025
commit
37338e442f
|
@ -172,12 +172,11 @@ set_target_properties(romfs PROPERTIES LINKER_LANGUAGE C)
|
|||
find_program(SHELLCHECK_PATH shellcheck)
|
||||
|
||||
if(SHELLCHECK_PATH)
|
||||
# TODO: fix SC2039, SC2086, SC2166
|
||||
# TODO: fix SC2086, SC2166
|
||||
add_custom_target(shellcheck
|
||||
COMMAND ${SHELLCHECK_PATH} --shell=sh
|
||||
--exclude=SC2121 # SC2121: To assign a variable, use just 'var=value'
|
||||
--exclude=SC2086 # SC2086: Double quote to prevent globbing and word splitting.
|
||||
--exclude=SC2039 # SC2039: In POSIX sh, == in place of = is undefined.
|
||||
--exclude=SC2166 # SC2166: Prefer [ p ] || [ q ] as [ p -o q ] is not well defined.
|
||||
--exclude=SC2154 # SC2154: <var> is referenced but not assigned (NuttX uses different asssignment)
|
||||
init.d/*
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 3
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.5
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
# TODO tune roll/pitch separately
|
||||
param set MC_ROLL_P 7.0
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 4
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 6
|
||||
param set BAT_V_EMPTY 3.5
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 3
|
||||
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_PITCH_P 4.0
|
||||
param set MC_PITCHRATE_P 0.24
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_AUX_DIS5 950
|
||||
param set PWM_RATE 400
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.0
|
||||
param set MC_ROLLRATE_P 0.12
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.19
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_MAX 2000
|
||||
param set PWM_RATE 400
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_MAX 2000
|
||||
param set PWM_RATE 400
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_AUX_DIS5 950
|
||||
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.5
|
||||
param set MC_ROLLRATE_P 0.15
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.15
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_THR_CRUISE 65.0
|
||||
param set FW_PR_P 0.08
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MAX 22.0
|
||||
param set FW_AIRSPD_MIN 14.0
|
||||
|
|
|
@ -12,7 +12,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_AUX_DISARMED 1000
|
||||
param set PWM_AUX_MAX 2000
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set CBRK_AIRSPD_CHK 162128
|
||||
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_CAPACITY 23000
|
||||
param set BAT_N_CELLS 4
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
sh /etc/init.d/rc.mc_defaults
|
||||
set MIXER coax
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.5
|
||||
param set MC_ROLLRATE_P 0.17
|
||||
|
|
|
@ -23,7 +23,7 @@ set MIXER blade130
|
|||
|
||||
#set PWM_OUT 1234
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set ATT_BIAS_MAX 0.0
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_AUX_RATE 50
|
||||
param set PWM_RATE 50
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MIN 10
|
||||
param set FW_AIRSPD_TRIM 15
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MIN 10
|
||||
param set FW_AIRSPD_TRIM 15
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
|
||||
set VEHICLE_TYPE mc
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set NAV_ACC_RAD 2.0
|
||||
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MAX 15
|
||||
param set FW_AIRSPD_MIN 10
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MIN 13
|
||||
param set FW_AIRSPD_TRIM 15
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MIN 15
|
||||
param set FW_AIRSPD_TRIM 20
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 2
|
||||
param set FW_AIRSPD_MAX 15
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MAX 30
|
||||
param set FW_AIRSPD_MIN 13
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MIN 15
|
||||
param set FW_AIRSPD_TRIM 20
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
|
||||
####################################
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MAX 25
|
||||
param set FW_AIRSPD_MIN 12.5
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_AUX_RATE 50
|
||||
fi
|
||||
|
|
|
@ -12,7 +12,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 8.0
|
||||
param set MC_ROLLRATE_P 0.08
|
||||
|
|
|
@ -15,7 +15,7 @@ sh /etc/init.d/4002_quad_x_mount
|
|||
# see http://www.zhiyun-tech.com/uploadfile/datedown/instruction/Tiny2_English_instructionV1.03.pdf
|
||||
# under Gimbal Connection Instruction
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_AUX_DISARMED 1520
|
||||
param set PWM_AUX_MIN 1020
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set ATT_BIAS_MAX 0.0
|
||||
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.15
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.15
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.16
|
||||
|
|
|
@ -20,7 +20,7 @@ sh /etc/init.d/rc.mc_defaults
|
|||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set MC_ROLL_P 6.5
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.5
|
||||
param set MC_ROLLRATE_P 0.18
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
# tuning
|
||||
param set MC_PITCHRATE_P 0.11
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.5
|
||||
param set MC_ROLLRATE_P 0.14
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.5
|
||||
param set MC_ROLLRATE_P 0.14
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 8.0
|
||||
param set MC_ROLLRATE_P 0.08
|
||||
|
|
|
@ -26,7 +26,7 @@ set MAV_TYPE 2
|
|||
|
||||
set PWM_OUT 1234
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set ATT_BIAS_MAX 0.0
|
||||
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 6
|
||||
|
||||
|
|
|
@ -19,7 +19,7 @@ sh /etc/init.d/rc.mc_defaults
|
|||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
|
|
|
@ -15,7 +15,7 @@ sh /etc/init.d/rc.mc_defaults
|
|||
set MIXER zmr250
|
||||
set PWM_OUT 1234
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set CBRK_IO_SAFETY 22027
|
||||
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 1
|
||||
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
# @maintainer Dennis Shtatov <densht@gmail.com>
|
||||
#
|
||||
sh /etc/init.d/4001_quad_x
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 1
|
||||
param set BAT_CAPACITY 240
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
|
||||
sh /etc/init.d/rc.ugv_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 2
|
||||
|
||||
|
|
|
@ -23,7 +23,7 @@ sh /etc/init.d/rc.ugv_defaults
|
|||
# This section can be enabled once tuning parameters for this particular
|
||||
# rover model are known. It allows to configure default gains via the GUI.
|
||||
#
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
# PWM default value for "disarmed" mode.
|
||||
# This centers the steering and throttle, which means
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
sh /etc/init.d/rc.ugv_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_N_CELLS 7
|
||||
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
|
||||
set VEHICLE_TYPE fw
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for fixed wing UAVs.
|
||||
|
|
|
@ -30,7 +30,7 @@ then
|
|||
set MIXER_AUX none
|
||||
fi
|
||||
|
||||
if [ $USE_IO == no ]
|
||||
if [ $USE_IO = no ]
|
||||
then
|
||||
set MIXER_AUX none
|
||||
fi
|
||||
|
@ -38,12 +38,12 @@ fi
|
|||
#
|
||||
# Set the default output mode if none was set.
|
||||
#
|
||||
if [ $OUTPUT_MODE == none ]
|
||||
if [ $OUTPUT_MODE = none ]
|
||||
then
|
||||
if [ $USE_IO == yes ]
|
||||
if [ $USE_IO = yes ]
|
||||
then
|
||||
# Enable IO output only if IO is present.
|
||||
if [ $IO_PRESENT == yes ]
|
||||
if [ $IO_PRESENT = yes ]
|
||||
then
|
||||
set OUTPUT_MODE io
|
||||
fi
|
||||
|
@ -53,17 +53,17 @@ then
|
|||
fi
|
||||
|
||||
#
|
||||
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output.
|
||||
# If OUTPUT_MODE = none then something is wrong with setup and we shouldn't try to enable output.
|
||||
#
|
||||
if [ $OUTPUT_MODE != none ]
|
||||
then
|
||||
if [ $OUTPUT_MODE == mkblctrl ]
|
||||
if [ $OUTPUT_MODE = mkblctrl ]
|
||||
then
|
||||
if [ $MKBLCTRL_MODE == x ]
|
||||
if [ $MKBLCTRL_MODE = x ]
|
||||
then
|
||||
set MKBLCTRL_ARG "-mkmode x"
|
||||
fi
|
||||
if [ $MKBLCTRL_MODE == + ]
|
||||
if [ $MKBLCTRL_MODE = + ]
|
||||
then
|
||||
set MKBLCTRL_ARG "-mkmode +"
|
||||
fi
|
||||
|
@ -75,7 +75,7 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == hil -o $OUTPUT_MODE == sim ]
|
||||
if [ $OUTPUT_MODE = hil -o $OUTPUT_MODE = sim ]
|
||||
then
|
||||
if ! pwm_out_sim start
|
||||
then
|
||||
|
@ -84,7 +84,7 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == fmu ]
|
||||
if [ $OUTPUT_MODE = fmu ]
|
||||
then
|
||||
if ! fmu mode_$FMU_MODE $FMU_ARGS
|
||||
then
|
||||
|
@ -94,7 +94,7 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == uavcan_esc ]
|
||||
if [ $OUTPUT_MODE = uavcan_esc ]
|
||||
then
|
||||
if param compare UAVCAN_ENABLE 0
|
||||
then
|
||||
|
@ -102,7 +102,7 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ]
|
||||
if [ $OUTPUT_MODE = io -o $OUTPUT_MODE = uavcan_esc ]
|
||||
then
|
||||
sh /etc/init.d/rc.io
|
||||
fi
|
||||
|
@ -110,7 +110,7 @@ then
|
|||
#
|
||||
# Start IO for RC input if needed.
|
||||
#
|
||||
if [ $IO_PRESENT == yes ]
|
||||
if [ $IO_PRESENT = yes ]
|
||||
then
|
||||
if [ $OUTPUT_MODE != io ]
|
||||
then
|
||||
|
@ -124,12 +124,12 @@ then
|
|||
#
|
||||
# Load main mixer.
|
||||
#
|
||||
if [ $MIXER_AUX == none -a $USE_IO == yes ]
|
||||
if [ $MIXER_AUX = none -a $USE_IO = yes ]
|
||||
then
|
||||
set MIXER_AUX ${MIXER}
|
||||
fi
|
||||
|
||||
if [ "$MIXER_FILE" == none ]
|
||||
if [ "$MIXER_FILE" = none ]
|
||||
then
|
||||
if [ -f ${SDCARD_MIXERS_PATH}/${MIXER}.main.mix ]
|
||||
then
|
||||
|
@ -146,19 +146,19 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == mkblctrl ]
|
||||
if [ $OUTPUT_MODE = mkblctrl ]
|
||||
then
|
||||
set OUTPUT_DEV /dev/mkblctrl0
|
||||
else
|
||||
set OUTPUT_DEV /dev/pwm_output0
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == uavcan_esc ]
|
||||
if [ $OUTPUT_MODE = uavcan_esc ]
|
||||
then
|
||||
set OUTPUT_DEV /dev/uavcan/esc
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == tap_esc ]
|
||||
if [ $OUTPUT_MODE = tap_esc ]
|
||||
then
|
||||
set OUTPUT_DEV /dev/tap_esc
|
||||
fi
|
||||
|
@ -311,7 +311,7 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
|
||||
if [ $OUTPUT_MODE = fmu -o $OUTPUT_MODE = io ]
|
||||
then
|
||||
if [ $PWM_OUT != none ]
|
||||
then
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#
|
||||
# PX4IO interface init script.
|
||||
#
|
||||
if [ $USE_IO == yes -a $IO_PRESENT == yes ]
|
||||
if [ $USE_IO = yes -a $IO_PRESENT = yes ]
|
||||
then
|
||||
if px4io start
|
||||
then
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
|
||||
set VEHICLE_TYPE mc
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set NAV_ACC_RAD 2.0
|
||||
|
||||
|
|
|
@ -218,7 +218,7 @@ then
|
|||
# external LSM303D is rotated 270 degrees yaw
|
||||
lsm303d -X -R 6 start
|
||||
|
||||
if [ $BOARD_FMUV3 == 20 ]
|
||||
if [ $BOARD_FMUV3 = 20 ]
|
||||
then
|
||||
# v2.0 internal MPU6000 is rotated 180 deg roll, 270 deg yaw
|
||||
mpu6000 -R 14 start
|
||||
|
@ -227,14 +227,14 @@ then
|
|||
hmc5883 -C -T -S -R 8 start
|
||||
fi
|
||||
|
||||
if [ $BOARD_FMUV3 == 21 ]
|
||||
if [ $BOARD_FMUV3 = 21 ]
|
||||
then
|
||||
# v2.1 internal MPU9250 is rotated 180 deg roll, 270 deg yaw
|
||||
mpu9250 -R 14 start
|
||||
fi
|
||||
|
||||
else
|
||||
# $BOARD_FMUV3 == 0 -> FMUv2
|
||||
# $BOARD_FMUV3 = 0 -> FMUv2
|
||||
|
||||
mpu6000 start
|
||||
|
||||
|
@ -364,7 +364,7 @@ fi
|
|||
# Begin Optional drivers #
|
||||
###############################################################################
|
||||
|
||||
if [ ${VEHICLE_TYPE} == fw -o ${VEHICLE_TYPE} == vtol ]
|
||||
if [ ${VEHICLE_TYPE} = fw -o ${VEHICLE_TYPE} = vtol ]
|
||||
then
|
||||
if param compare CBRK_AIRSPD_CHK 0
|
||||
then
|
||||
|
@ -374,7 +374,7 @@ then
|
|||
# detected as MS5525 because the chip manufacturer was so
|
||||
# clever to assign the same I2C address and skip a WHO_AM_I
|
||||
# register.
|
||||
if [ $BOARD_FMUV3 == 21 ]
|
||||
if [ $BOARD_FMUV3 = 21 ]
|
||||
then
|
||||
ms5525_airspeed start -b 2
|
||||
else
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
|
||||
set VEHICLE_TYPE ugv
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for UGVs.
|
||||
|
|
|
@ -8,15 +8,15 @@
|
|||
#
|
||||
# Fixed wing setup.
|
||||
#
|
||||
if [ $VEHICLE_TYPE == fw ]
|
||||
if [ $VEHICLE_TYPE = fw ]
|
||||
then
|
||||
if [ $MIXER == none ]
|
||||
if [ $MIXER = none ]
|
||||
then
|
||||
# Set default mixer for fixed wing if not defined.
|
||||
set MIXER AERT
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
# Set a default MAV_TYPE = 1 if not defined.
|
||||
set MAV_TYPE 1
|
||||
|
@ -35,40 +35,40 @@ fi
|
|||
#
|
||||
# Multicopter setup.
|
||||
#
|
||||
if [ $VEHICLE_TYPE == mc ]
|
||||
if [ $VEHICLE_TYPE = mc ]
|
||||
then
|
||||
if [ $MIXER == none ]
|
||||
if [ $MIXER = none ]
|
||||
then
|
||||
echo "MC mixer undefined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
# Set a default MAV_TYPE = 2 if not defined.
|
||||
set MAV_TYPE 2
|
||||
|
||||
# Use mixer to detect vehicle type
|
||||
if [ $MIXER == coax ]
|
||||
if [ $MIXER = coax ]
|
||||
then
|
||||
set MAV_TYPE 3
|
||||
fi
|
||||
if [ $MIXER == hexa_x -o $MIXER == hexa_+ ]
|
||||
if [ $MIXER = hexa_x -o $MIXER = hexa_+ ]
|
||||
then
|
||||
set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == hexa_cox ]
|
||||
if [ $MIXER = hexa_cox ]
|
||||
then
|
||||
set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == octo_x -o $MIXER == octo_+ ]
|
||||
if [ $MIXER = octo_x -o $MIXER = octo_+ ]
|
||||
then
|
||||
set MAV_TYPE 14
|
||||
fi
|
||||
if [ $MIXER == octo_cox -o $MIXER == octo_cox_w ]
|
||||
if [ $MIXER = octo_cox -o $MIXER = octo_cox_w ]
|
||||
then
|
||||
set MAV_TYPE 14
|
||||
fi
|
||||
if [ $MIXER == tri_y_yaw- -o $MIXER == tri_y_yaw+ ]
|
||||
if [ $MIXER = tri_y_yaw- -o $MIXER = tri_y_yaw+ ]
|
||||
then
|
||||
set MAV_TYPE 15
|
||||
fi
|
||||
|
@ -87,15 +87,15 @@ fi
|
|||
#
|
||||
# UGV setup.
|
||||
#
|
||||
if [ $VEHICLE_TYPE == ugv ]
|
||||
if [ $VEHICLE_TYPE = ugv ]
|
||||
then
|
||||
if [ $MIXER == none ]
|
||||
if [ $MIXER = none ]
|
||||
then
|
||||
# Set default mixer for UGV if not defined.
|
||||
set MIXER ugv_generic
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
# Set a default MAV_TYPE = 10 if not defined.
|
||||
set MAV_TYPE 10
|
||||
|
@ -114,24 +114,24 @@ fi
|
|||
#
|
||||
# VTOL setup.
|
||||
#
|
||||
if [ $VEHICLE_TYPE == vtol ]
|
||||
if [ $VEHICLE_TYPE = vtol ]
|
||||
then
|
||||
if [ $MIXER == none ]
|
||||
if [ $MIXER = none ]
|
||||
then
|
||||
echo "VTOL mixer undefined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
# Set a default MAV_TYPE = 19 if not defined.
|
||||
set MAV_TYPE 19
|
||||
|
||||
# Use mixer to detect vehicle type.
|
||||
if [ $MIXER == firefly6 ]
|
||||
if [ $MIXER = firefly6 ]
|
||||
then
|
||||
set MAV_TYPE 21
|
||||
fi
|
||||
if [ $MIXER == quad_x_pusher_vtol ]
|
||||
if [ $MIXER = quad_x_pusher_vtol ]
|
||||
then
|
||||
set MAV_TYPE 22
|
||||
fi
|
||||
|
@ -150,7 +150,7 @@ fi
|
|||
#
|
||||
# Generic setup (autostart ID not found).
|
||||
#
|
||||
if [ $VEHICLE_TYPE == none ]
|
||||
if [ $VEHICLE_TYPE = none ]
|
||||
then
|
||||
echo "No autostart ID found"
|
||||
ekf2 start
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
|
||||
set VEHICLE_TYPE vtol
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MIS_TAKEOFF_ALT 20
|
||||
param set MIS_YAW_TMT 10
|
||||
|
|
|
@ -163,7 +163,7 @@ fi
|
|||
if ! ver hwcmp CRAZYFLIE AEROCORE2
|
||||
then
|
||||
# Run no SD alarm.
|
||||
if [ $LOG_FILE == /dev/null ]
|
||||
if [ $LOG_FILE = /dev/null ]
|
||||
then
|
||||
# tune Make FS MBAGP
|
||||
tune_control play -t 2
|
||||
|
@ -335,7 +335,7 @@ else
|
|||
#
|
||||
# If autoconfig parameter was set, reset it and save parameters.
|
||||
#
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
# Run FMU as task on Pixracer and on boards with enough RAM.
|
||||
if ver hwcmp PX4FMU_V4 PX4FMU_V4PRO PX4FMU_V5
|
||||
|
@ -406,7 +406,7 @@ else
|
|||
fi
|
||||
fi
|
||||
|
||||
if [ $IO_PRESENT == no ]
|
||||
if [ $IO_PRESENT = no ]
|
||||
then
|
||||
echo "PX4IO update failed" >> $LOG_FILE
|
||||
# Error tune.
|
||||
|
@ -424,14 +424,14 @@ else
|
|||
set USE_IO yes
|
||||
fi
|
||||
|
||||
if [ $USE_IO == yes -a $IO_PRESENT == no ]
|
||||
if [ $USE_IO = yes -a $IO_PRESENT = no ]
|
||||
then
|
||||
echo "PX4IO not found" >> $LOG_FILE
|
||||
# Error tune.
|
||||
tune_control play -t 2
|
||||
fi
|
||||
|
||||
if [ $IO_PRESENT == no -o $USE_IO == no ]
|
||||
if [ $IO_PRESENT = no -o $USE_IO = no ]
|
||||
then
|
||||
rc_input start
|
||||
fi
|
||||
|
|
|
@ -46,7 +46,7 @@ then
|
|||
set BOARD_FMUV3 false
|
||||
fi
|
||||
|
||||
if [ $BOARD_FMUV3 == true ]
|
||||
if [ $BOARD_FMUV3 = true ]
|
||||
then
|
||||
# external L3GD20H is rotated 180 degrees yaw
|
||||
if l3gd20 -X -R 4 start
|
||||
|
|
|
@ -24,7 +24,7 @@ fi
|
|||
# Try to mount the microSD card.
|
||||
#
|
||||
mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
if [ $? == 0 ]
|
||||
if [ $? = 0 ]
|
||||
then
|
||||
echo "[i] card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
set VEHICLE_TYPE fw
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for FW
|
||||
|
|
|
@ -16,7 +16,7 @@ then
|
|||
|
||||
set OUTPUT_DEV /dev/pwm_output0
|
||||
|
||||
if [ $OUTPUT_MODE == tap_esc ]
|
||||
if [ $OUTPUT_MODE = tap_esc ]
|
||||
then
|
||||
set OUTPUT_DEV /dev/tap_esc
|
||||
fi
|
||||
|
@ -40,7 +40,7 @@ else
|
|||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
|
||||
if [ $OUTPUT_MODE = fmu -o $OUTPUT_MODE = io ]
|
||||
then
|
||||
if [ $PWM_OUT != none ]
|
||||
then
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
set VEHICLE_TYPE mc
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set PWM_DISARMED 900
|
||||
param set PWM_MIN 1075
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
set VEHICLE_TYPE vtol
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.0
|
||||
param set MC_PITCH_P 6.0
|
||||
|
|
|
@ -125,7 +125,7 @@ sh /etc/init.d/rc.autostart
|
|||
#
|
||||
# If autoconfig parameter was set, reset it and save parameters
|
||||
#
|
||||
if [ $AUTOCNF == yes ]
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
|
@ -135,9 +135,9 @@ unset AUTOCNF
|
|||
#
|
||||
# Set default output if not set
|
||||
#
|
||||
if [ $OUTPUT_MODE == none ]
|
||||
if [ $OUTPUT_MODE = none ]
|
||||
then
|
||||
if [ $USE_IO == yes ]
|
||||
if [ $USE_IO = yes ]
|
||||
then
|
||||
set OUTPUT_MODE io
|
||||
else
|
||||
|
@ -181,17 +181,17 @@ mavlink start -r 60000 -d /dev/ttyACM0 -m config
|
|||
#
|
||||
# Fixed wing setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == fw ]
|
||||
if [ $VEHICLE_TYPE = fw ]
|
||||
then
|
||||
echo "INFO [init] Fixedwing"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
if [ $MIXER = none ]
|
||||
then
|
||||
# Set default mixer for fixed wing if not defined
|
||||
set MIXER AERT
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
# Use MAV_TYPE = 1 (fixed wing) if not defined
|
||||
set MAV_TYPE 1
|
||||
|
@ -209,50 +209,50 @@ fi
|
|||
#
|
||||
# Multicopters setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == mc ]
|
||||
if [ $VEHICLE_TYPE = mc ]
|
||||
then
|
||||
echo "INFO [init] Multicopter"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
if [ $MIXER = none ]
|
||||
then
|
||||
echo "INFO [init] Mixer undefined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
# Use mixer to detect vehicle type
|
||||
if [ $MIXER == quad_x -o $MIXER == quad_+ ]
|
||||
if [ $MIXER = quad_x -o $MIXER = quad_+ ]
|
||||
then
|
||||
set MAV_TYPE 2
|
||||
fi
|
||||
if [ $MIXER == quad_w ]
|
||||
if [ $MIXER = quad_w ]
|
||||
then
|
||||
set MAV_TYPE 2
|
||||
fi
|
||||
if [ $MIXER == quad_h ]
|
||||
if [ $MIXER = quad_h ]
|
||||
then
|
||||
set MAV_TYPE 2
|
||||
fi
|
||||
if [ $MIXER == tri_y_yaw- -o $MIXER == tri_y_yaw+ ]
|
||||
if [ $MIXER = tri_y_yaw- -o $MIXER = tri_y_yaw+ ]
|
||||
then
|
||||
set MAV_TYPE 15
|
||||
fi
|
||||
if [ $MIXER == hexa_x -o $MIXER == hexa_+ ]
|
||||
if [ $MIXER = hexa_x -o $MIXER = hexa_+ ]
|
||||
then
|
||||
set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == hexa_cox ]
|
||||
if [ $MIXER = hexa_cox ]
|
||||
then
|
||||
set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == octo_x -o $MIXER == octo_+ ]
|
||||
if [ $MIXER = octo_x -o $MIXER = octo_+ ]
|
||||
then
|
||||
set MAV_TYPE 14
|
||||
fi
|
||||
fi
|
||||
|
||||
# Still no MAV_TYPE found
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
echo "WARN [init] Unknown MAV_TYPE"
|
||||
param set MAV_TYPE 2
|
||||
|
@ -270,34 +270,34 @@ fi
|
|||
#
|
||||
# VTOL setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == vtol ]
|
||||
if [ $VEHICLE_TYPE = vtol ]
|
||||
then
|
||||
echo "INFO [init] VTOL"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
if [ $MIXER = none ]
|
||||
then
|
||||
echo "WARN [init] VTOL mixer undefined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
# Use mixer to detect vehicle type
|
||||
if [ $MIXER == caipirinha_vtol ]
|
||||
if [ $MIXER = caipirinha_vtol ]
|
||||
then
|
||||
set MAV_TYPE 19
|
||||
fi
|
||||
if [ $MIXER == firefly6 ]
|
||||
if [ $MIXER = firefly6 ]
|
||||
then
|
||||
set MAV_TYPE 21
|
||||
fi
|
||||
if [ $MIXER == quad_x_pusher_vtol ]
|
||||
if [ $MIXER = quad_x_pusher_vtol ]
|
||||
then
|
||||
set MAV_TYPE 22
|
||||
fi
|
||||
fi
|
||||
|
||||
# Still no MAV_TYPE found
|
||||
if [ $MAV_TYPE == none ]
|
||||
if [ $MAV_TYPE = none ]
|
||||
then
|
||||
echo "WARN [init] Unknown MAV_TYPE"
|
||||
param set MAV_TYPE 19
|
||||
|
@ -315,7 +315,7 @@ fi
|
|||
#
|
||||
# UGV/Rover setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == ugv ]
|
||||
if [ $VEHICLE_TYPE = ugv ]
|
||||
then
|
||||
# 10 is MAV_TYPE_GROUND_ROVER
|
||||
set MAV_TYPE 10
|
||||
|
|
|
@ -6,7 +6,7 @@ set SERIAL_DEV none
|
|||
{% for serial_device in serial_devices -%}
|
||||
if param compare "$PRT" {{ serial_device.index }}
|
||||
then
|
||||
if [ "x$PRT_{{ serial_device.tag }}_" == "x" ]
|
||||
if [ "x$PRT_{{ serial_device.tag }}_" = "x" ]
|
||||
then
|
||||
set SERIAL_DEV {{ serial_device.device }}
|
||||
set BAUD_PARAM SER_{{ serial_device.tag }}_BAUD
|
||||
|
|
Loading…
Reference in New Issue