mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 01:12:31 +00:00
ROMFS: Set up LL40S startup to reserve the pins it uses
This commit is contained in:
@@ -127,6 +127,7 @@ then
|
||||
set FAILSAFE_AUX none
|
||||
set MK_MODE none
|
||||
set FMU_MODE pwm
|
||||
set AUX_MODE pwm
|
||||
set MAVLINK_F default
|
||||
set EXIT_ON_END no
|
||||
set MAV_TYPE none
|
||||
@@ -451,17 +452,6 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start sensors depending on the interface being up
|
||||
if param compare SENS_EN_LL40LS 1
|
||||
then
|
||||
if pwm_input start
|
||||
then
|
||||
if ll40ls start pwm
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $MAVLINK_F == default ]
|
||||
then
|
||||
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
|
||||
@@ -517,6 +507,19 @@ then
|
||||
#
|
||||
sh /etc/init.d/rc.logging
|
||||
|
||||
# Sensors on the PWM interface bank
|
||||
if param compare SENS_EN_LL40LS 1
|
||||
then
|
||||
if pwm_input start
|
||||
then
|
||||
if ll40ls start pwm
|
||||
then
|
||||
# Reserve the last two pins
|
||||
set AUX_MODE pwm4
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start up ARDrone Motor interface
|
||||
#
|
||||
|
||||
Reference in New Issue
Block a user