mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
PX4: removed driver startup from rc.APM
moved to AP_BoardConfig instead
This commit is contained in:
parent
0d59935847
commit
00f3113e83
@ -250,18 +250,6 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
echo "Starting APM sensors"
|
||||
|
||||
if ms5611 start
|
||||
then
|
||||
echo "ms5611 started OK"
|
||||
else
|
||||
echo "no ms5611 found"
|
||||
echo "No ms5611 found" >> $logfile
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
if adc start
|
||||
then
|
||||
echo "adc started OK"
|
||||
@ -270,232 +258,6 @@ else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
|
||||
if [ $BOARD == FMUv1 ]
|
||||
then
|
||||
echo "Starting FMUv1 sensors"
|
||||
if hmc5883 -C -T -X start
|
||||
then
|
||||
echo "Have external hmc5883"
|
||||
else
|
||||
echo "No external hmc5883"
|
||||
fi
|
||||
if hmc5883 -C -T -I start
|
||||
then
|
||||
echo "Have internal hmc5883"
|
||||
else
|
||||
echo "No internal hmc5883"
|
||||
fi
|
||||
if mpu6000 start
|
||||
then
|
||||
echo "mpu6000 started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
if l3gd20 start
|
||||
then
|
||||
echo "l3gd20 started OK"
|
||||
else
|
||||
echo "No l3gd20"
|
||||
echo "No l3gd20" >> $logfile
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $BOARD == FMUv2 ]
|
||||
then
|
||||
echo "Starting FMUv2 sensors"
|
||||
if hmc5883 -C -T -X start
|
||||
then
|
||||
echo "Have external hmc5883"
|
||||
else
|
||||
echo "No external hmc5883"
|
||||
fi
|
||||
if hmc5883 -C -T -I -R 4 start
|
||||
then
|
||||
echo "Have internal hmc5883"
|
||||
else
|
||||
echo "No internal hmc5883"
|
||||
fi
|
||||
|
||||
# external MPU6000 is rotated YAW_180 from standard
|
||||
if mpu6000 -X -R 4 start
|
||||
then
|
||||
echo "Found MPU6000 external"
|
||||
set HAVE_FMUV3 true
|
||||
else
|
||||
if mpu9250 -X -R 4 start
|
||||
then
|
||||
echo "Found MPU9250 external"
|
||||
set HAVE_FMUV3 true
|
||||
else
|
||||
echo "No MPU6000 or MPU9250 external"
|
||||
set HAVE_FMUV3 false
|
||||
fi
|
||||
fi
|
||||
if [ $HAVE_FMUV3 == true ]
|
||||
then
|
||||
# external L3GD20 is rotated YAW_180 from standard
|
||||
if l3gd20 -X -R 4 start
|
||||
then
|
||||
echo "l3gd20 external started OK"
|
||||
else
|
||||
echo "No l3gd20"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
# external LSM303D is rotated YAW_270 from standard
|
||||
if lsm303d -a 16 -X -R 6 start
|
||||
then
|
||||
echo "lsm303d external started OK"
|
||||
else
|
||||
echo "No lsm303d"
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
# internal MPU6000 is rotated ROLL_180_YAW_270 from standard
|
||||
if mpu6000 -R 14 start
|
||||
then
|
||||
echo "Found MPU6000 internal"
|
||||
else
|
||||
if mpu9250 -R 14 start
|
||||
then
|
||||
echo "Found MPU9250 internal"
|
||||
else
|
||||
echo "No MPU6000 or MPU9250"
|
||||
echo "No MPU6000 or MPU9250" >> $logfile
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
fi
|
||||
if hmc5883 -C -T -S -R 8 start
|
||||
then
|
||||
echo "Found SPI hmc5883"
|
||||
fi
|
||||
else
|
||||
if mpu6000 start
|
||||
then
|
||||
echo "Found MPU6000"
|
||||
else
|
||||
if mpu9250 start
|
||||
then
|
||||
echo "Found MPU9250"
|
||||
else
|
||||
echo "No MPU6000 or MPU9250"
|
||||
echo "No MPU9250" >> $logfile
|
||||
fi
|
||||
fi
|
||||
if l3gd20 start
|
||||
then
|
||||
echo "l3gd20 started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
if lsm303d -a 16 start
|
||||
then
|
||||
echo "lsm303d started OK"
|
||||
else
|
||||
sh /etc/init.d/rc.error
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
if [ $BOARD == FMUv4 ]
|
||||
then
|
||||
echo "Starting FMUv4 sensors"
|
||||
if hmc5883 -C -T -X start
|
||||
then
|
||||
echo "Have external hmc5883"
|
||||
else
|
||||
echo "No external hmc5883"
|
||||
fi
|
||||
if hmc5883 -C -T -S -R 2 start
|
||||
then
|
||||
echo "Have SPI hmc5883"
|
||||
else
|
||||
echo "No SPI hmc5883"
|
||||
fi
|
||||
|
||||
if mpu6000 -R 2 -T 20608 start
|
||||
then
|
||||
echo "Found ICM-20608 internal"
|
||||
fi
|
||||
|
||||
if mpu9250 -R 2 start
|
||||
then
|
||||
echo "Found mpu9250 internal"
|
||||
fi
|
||||
fi
|
||||
|
||||
# optional ETS airspeed sensor
|
||||
if ets_airspeed start
|
||||
then
|
||||
echo "Found ETS airspeed sensor"
|
||||
fi
|
||||
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "Found MEAS airspeed sensor"
|
||||
else
|
||||
if meas_airspeed start -b 2
|
||||
then
|
||||
echo "Found MEAS airspeed sensor (bus2)"
|
||||
fi
|
||||
fi
|
||||
|
||||
# optional Range Finder sensor
|
||||
if ll40ls -X start
|
||||
then
|
||||
echo "Found external ll40ls sensor"
|
||||
fi
|
||||
|
||||
if ll40ls -I start
|
||||
then
|
||||
echo "Found internal ll40ls sensor"
|
||||
fi
|
||||
|
||||
if trone start
|
||||
then
|
||||
echo "Found trone sensor"
|
||||
fi
|
||||
|
||||
if mb12xx start
|
||||
then
|
||||
echo "Found mb12xx sensor"
|
||||
fi
|
||||
|
||||
# optional PX4Flow sensor
|
||||
if [ -f /bin/px4flow ]
|
||||
then
|
||||
if px4flow start
|
||||
then
|
||||
echo "Found px4flow sensor"
|
||||
fi
|
||||
fi
|
||||
|
||||
# optional PWM input driver
|
||||
if pwm_input start
|
||||
then
|
||||
echo "started pwm_input driver"
|
||||
fi
|
||||
|
||||
# optional oreo leds
|
||||
if [ -f /bin/oreoled ]
|
||||
then
|
||||
if oreoled start autoupdate
|
||||
then
|
||||
echo "oreoled started OK"
|
||||
fi
|
||||
fi
|
||||
|
||||
# optional smbus battery monitor
|
||||
if batt_smbus -b 2 start
|
||||
then
|
||||
echo "Found batt_smbus"
|
||||
fi
|
||||
|
||||
# optional irlock
|
||||
if irlock start
|
||||
then
|
||||
echo "irlock started"
|
||||
fi
|
||||
|
||||
echo Starting ArduPilot $deviceA $deviceC $deviceD
|
||||
if ArduPilot -d $deviceA -d2 $deviceC -d3 $deviceD start
|
||||
then
|
||||
|
Loading…
Reference in New Issue
Block a user