mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Moved to USART1 for the main console, starting a 2nd NSH instance on USB if needed, reworked start scripts to not fall over
This commit is contained in:
parent
3005c8aae0
commit
cfa9054aa4
@ -97,11 +97,9 @@ multirotor_att_control start
|
||||
# Start logging
|
||||
#
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
blinkm systemstate
|
||||
fi
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
|
||||
# Exit, because /dev/ttyS0 is needed for MAVLink
|
||||
exit
|
||||
|
||||
@ -88,7 +88,7 @@ pwm -u 400 -m 0xff
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
# Start logging once armed
|
||||
#
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
|
||||
@ -2,12 +2,6 @@
|
||||
#
|
||||
# Flight startup script for PX4FMU on PX4IOAR carrier board.
|
||||
#
|
||||
|
||||
# Disable the USB interface
|
||||
set USB no
|
||||
|
||||
# Disable autostarting other apps
|
||||
set MODE ardrone
|
||||
|
||||
echo "[init] doing PX4IOAR startup..."
|
||||
|
||||
@ -70,25 +64,14 @@ multirotor_att_control start
|
||||
ardrone_interface start -d /dev/ttyS1
|
||||
|
||||
#
|
||||
# Start logging
|
||||
# Start logging once armed
|
||||
#
|
||||
sdlog start -s 10
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# Start GPS capture
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
||||
|
||||
#
|
||||
# startup is done; we don't want the shell because we
|
||||
@ -96,4 +79,8 @@ fi
|
||||
#
|
||||
echo "[init] startup done"
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
|
||||
# Exit, because /dev/ttyS0 is needed for MAVLink
|
||||
exit
|
||||
|
||||
@ -2,12 +2,6 @@
|
||||
#
|
||||
# Flight startup script for PX4FMU on PX4IOAR carrier board.
|
||||
#
|
||||
|
||||
# Disable the USB interface
|
||||
set USB no
|
||||
|
||||
# Disable autostarting other apps
|
||||
set MODE ardrone
|
||||
|
||||
echo "[init] doing PX4IOAR startup..."
|
||||
|
||||
@ -84,6 +78,11 @@ flow_speed_control start
|
||||
# Fire up the AR.Drone interface.
|
||||
#
|
||||
ardrone_interface start -d /dev/ttyS1
|
||||
|
||||
#
|
||||
# Start logging once armed
|
||||
#
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# startup is done; we don't want the shell because we
|
||||
@ -91,4 +90,8 @@ ardrone_interface start -d /dev/ttyS1
|
||||
#
|
||||
echo "[init] startup done"
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
|
||||
# Exit, because /dev/ttyS0 is needed for MAVLink
|
||||
exit
|
||||
|
||||
@ -2,10 +2,6 @@
|
||||
#
|
||||
# Flight startup script for PX4FMU+PX4IO on an F330 quad.
|
||||
#
|
||||
|
||||
# disable USB and autostart
|
||||
set USB no
|
||||
set MODE custom
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
@ -60,34 +56,37 @@ commander start
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
#
|
||||
# This sets a PWM right after startup (regardless of safety button)
|
||||
#
|
||||
px4io idle 900 900 900 900
|
||||
|
||||
pwm -u 400 -m 0xff
|
||||
|
||||
#
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
|
||||
|
||||
#
|
||||
# The values are for spinning motors when armed using DJI ESCs
|
||||
#
|
||||
px4io min 1200 1200 1200 1200
|
||||
|
||||
#
|
||||
# Upper limits could be higher, this is on the safe side
|
||||
#
|
||||
px4io max 1800 1800 1800 1800
|
||||
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
|
||||
else
|
||||
# SOS
|
||||
tone_alarm 6
|
||||
fi
|
||||
|
||||
#
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# This sets a PWM right after startup (regardless of safety button)
|
||||
#
|
||||
px4io idle 900 900 900 900
|
||||
|
||||
#
|
||||
# The values are for spinning motors when armed using DJI ESCs
|
||||
#
|
||||
px4io min 1200 1200 1200 1200
|
||||
|
||||
#
|
||||
# Upper limits could be higher, this is on the safe side
|
||||
#
|
||||
px4io max 1800 1800 1800 1800
|
||||
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
|
||||
@ -61,7 +61,13 @@ then
|
||||
#
|
||||
# Start terminal
|
||||
#
|
||||
sercon
|
||||
if sercon
|
||||
then
|
||||
echo "USB connected"
|
||||
else
|
||||
# second attempt
|
||||
sercon &
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
@ -128,45 +134,84 @@ fi
|
||||
if param compare SYS_AUTOSTART 1
|
||||
then
|
||||
sh /etc/init.d/01_fmu_quad_x
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2
|
||||
then
|
||||
sh /etc/init.d/02_io_quad_x
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 8
|
||||
then
|
||||
sh /etc/init.d/08_ardrone
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 9
|
||||
then
|
||||
sh /etc/init.d/09_ardrone_flow
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10
|
||||
then
|
||||
sh /etc/init.d/10_io_f330
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 15
|
||||
then
|
||||
sh /etc/init.d/15_io_tbs
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 30
|
||||
then
|
||||
sh /etc/init.d/30_io_camflyer
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 31
|
||||
then
|
||||
sh /etc/init.d/31_io_phantom
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
|
||||
# If none of the autostart scripts triggered, get a minimal setup
|
||||
if [ $MODE == autostart ]
|
||||
then
|
||||
# Telemetry port is on both FMU boards ttyS1
|
||||
mavlink start -b 57600 -d /dev/ttyS1
|
||||
|
||||
# Start commander
|
||||
commander start
|
||||
|
||||
# Start px4io if present
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO driver started"
|
||||
else
|
||||
if fmu mode_serial
|
||||
then
|
||||
echo "FMU driver started"
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start sensors
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
# Start one of the estimators
|
||||
attitude_estimator_ekf start
|
||||
|
||||
# Start GPS
|
||||
gps start
|
||||
|
||||
fi
|
||||
|
||||
# End of autostart
|
||||
fi
|
||||
|
||||
@ -368,7 +368,7 @@ CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_START_YEAR=1970
|
||||
CONFIG_START_MONTH=1
|
||||
CONFIG_START_DAY=1
|
||||
# CONFIG_DEV_CONSOLE is not set
|
||||
CONFIG_DEV_CONSOLE=y
|
||||
# CONFIG_MUTEX_TYPES is not set
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
@ -476,11 +476,11 @@ CONFIG_ARCH_HAVE_USART6=y
|
||||
CONFIG_MCU_SERIAL=y
|
||||
CONFIG_STANDARD_SERIAL=y
|
||||
CONFIG_SERIAL_NPOLLWAITERS=2
|
||||
# CONFIG_USART1_SERIAL_CONSOLE is not set
|
||||
CONFIG_USART1_SERIAL_CONSOLE=y
|
||||
# CONFIG_USART2_SERIAL_CONSOLE is not set
|
||||
# CONFIG_UART5_SERIAL_CONSOLE is not set
|
||||
# CONFIG_USART6_SERIAL_CONSOLE is not set
|
||||
CONFIG_NO_SERIAL_CONSOLE=y
|
||||
# CONFIG_NO_SERIAL_CONSOLE is not set
|
||||
|
||||
#
|
||||
# USART1 Configuration
|
||||
@ -550,7 +550,7 @@ CONFIG_USBDEV_MAXPOWER=500
|
||||
# CONFIG_USBDEV_COMPOSITE is not set
|
||||
# CONFIG_PL2303 is not set
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_CONSOLE=y
|
||||
CONFIG_CDCACM_CONSOLE=n
|
||||
CONFIG_CDCACM_EP0MAXPACKET=64
|
||||
CONFIG_CDCACM_EPINTIN=1
|
||||
CONFIG_CDCACM_EPINTIN_FSSIZE=64
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user