forked from Archive/PX4-Autopilot
ROMFS:Removed FMUv1 from rcS etal
This commit is contained in:
parent
c0bff500fe
commit
62a2351a72
|
@ -121,10 +121,6 @@ then
|
|||
fi
|
||||
|
||||
# This is a FMUv2+ thing
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
set MIXER_AUX none
|
||||
fi
|
||||
|
||||
#MindPX has not aux mixer
|
||||
if ver hwcmp MINDPX_V2
|
||||
|
|
|
@ -11,10 +11,6 @@ px4io recovery
|
|||
# Adjust PX4IO update rate limit
|
||||
#
|
||||
set PX4IO_LIMIT 400
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
set PX4IO_LIMIT 200
|
||||
fi
|
||||
|
||||
if px4io limit ${PX4IO_LIMIT}
|
||||
then
|
||||
|
|
|
@ -1,12 +1,8 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard startup script for PX4FMU v1, v2, v3, v4 onboard sensor drivers.
|
||||
# Standard startup script for PX4FMU v2, v3, v4 onboard sensor drivers.
|
||||
#
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
ms5611 start
|
||||
else
|
||||
if ver hwcmp AEROFC_V1
|
||||
then
|
||||
# Aero FC uses separate driver
|
||||
|
@ -40,13 +36,7 @@ else
|
|||
|
||||
# Blacksheep telemetry
|
||||
bst start
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp AEROFC_V1
|
||||
then
|
||||
# Aero FC uses separate driver
|
||||
else
|
||||
adc start
|
||||
fi
|
||||
|
||||
|
@ -184,28 +174,6 @@ then
|
|||
bmp280 -I start
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
# FMUv1
|
||||
mpu6000 start
|
||||
l3gd20 start
|
||||
|
||||
# MAG selection
|
||||
if param compare SENS_EXT_MAG 2
|
||||
then
|
||||
hmc5883 -C -I start
|
||||
else
|
||||
# Use only external as primary
|
||||
if param compare SENS_EXT_MAG 1
|
||||
then
|
||||
hmc5883 -C -X start
|
||||
else
|
||||
# auto-detect the primary, prefer external
|
||||
hmc5883 start
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp MINDPX_V2
|
||||
then
|
||||
# External I2C bus
|
||||
|
|
|
@ -13,7 +13,7 @@ set +e
|
|||
#
|
||||
# NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS.
|
||||
#
|
||||
# UART mapping on FMUv1/2/3/4:
|
||||
# UART mapping on FMUv2/3/4:
|
||||
#
|
||||
# UART1 /dev/ttyS0 IO debug
|
||||
# USART2 /dev/ttyS1 TELEM1 (flow control)
|
||||
|
@ -418,11 +418,6 @@ then
|
|||
# Need IO for output but it not present, disable output
|
||||
set OUTPUT_MODE none
|
||||
|
||||
# Avoid using ttyS0 for MAVLink on FMUv1
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
set FMU_MODE serial
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == ardrone ]
|
||||
|
@ -438,10 +433,6 @@ then
|
|||
if [ $HIL == yes ]
|
||||
then
|
||||
set OUTPUT_MODE hil
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
set FMU_MODE serial
|
||||
fi
|
||||
else
|
||||
gps start
|
||||
fi
|
||||
|
@ -559,18 +550,6 @@ then
|
|||
echo "FMU start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == mkblctrl ]
|
||||
|
@ -628,18 +607,6 @@ then
|
|||
echo "FMU mode_${FMU_MODE} start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
@ -687,9 +654,6 @@ then
|
|||
#
|
||||
# MAVLink onboard / TELEM2
|
||||
#
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
else
|
||||
# XXX We need a better way for runtime eval of shell variables,
|
||||
# but this works for now
|
||||
if param compare SYS_COMPANION 10
|
||||
|
@ -750,7 +714,6 @@ then
|
|||
then
|
||||
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 1500000 -m onboard -r 10000 -x -f
|
||||
fi
|
||||
fi
|
||||
|
||||
unset MAVLINK_COMPANION_DEVICE
|
||||
|
||||
|
@ -811,12 +774,6 @@ then
|
|||
#
|
||||
# Logging
|
||||
#
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
if sdlog2 start -r 30 -a -b 2 -t
|
||||
then
|
||||
fi
|
||||
else
|
||||
if param compare SYS_LOGGER 0
|
||||
then
|
||||
# check if we should increase logging rate for ekf2 replay message logging
|
||||
|
@ -858,7 +815,6 @@ then
|
|||
unset LOGGER_BUF
|
||||
unset LOGGER_ARGS
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start up ARDrone Motor interface
|
||||
|
|
|
@ -1,14 +1,8 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard startup script for PX4FMU v1, v2, v3, v4 onboard sensor drivers.
|
||||
# Standard startup script for PX4FMU v2, v3, v4 onboard sensor drivers.
|
||||
#
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
if ms5611 start
|
||||
then
|
||||
fi
|
||||
else
|
||||
# Configure all I2C buses to 100 KHz as they
|
||||
# are all external or slow
|
||||
fmu i2c 1 100000
|
||||
|
@ -22,7 +16,6 @@ else
|
|||
if bst start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
if adc start
|
||||
then
|
||||
|
@ -116,39 +109,6 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
# FMUv1
|
||||
if mpu6000 start
|
||||
then
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
fi
|
||||
|
||||
# MAG selection
|
||||
if param compare SENS_EXT_MAG 2
|
||||
then
|
||||
if hmc5883 -C -I start
|
||||
then
|
||||
fi
|
||||
else
|
||||
# Use only external as primary
|
||||
if param compare SENS_EXT_MAG 1
|
||||
then
|
||||
if hmc5883 -C -X start
|
||||
then
|
||||
fi
|
||||
else
|
||||
# auto-detect the primary, prefer external
|
||||
if hmc5883 start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp MINDPX_V2
|
||||
then
|
||||
# External I2C bus
|
||||
|
|
Loading…
Reference in New Issue