mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 05:47:35 +08:00
Implemented new, simple system boot config and sane default value system based on two parameters evaluated at boot time
This commit is contained in:
+29
-6
@@ -3,10 +3,8 @@
|
||||
# Flight startup script for PX4FMU with PWM outputs.
|
||||
#
|
||||
|
||||
# Disable the USB interface
|
||||
# disable USB and autostart
|
||||
set USB no
|
||||
|
||||
# Disable autostarting other apps
|
||||
set MODE custom
|
||||
|
||||
echo "[init] doing PX4FMU Quad startup..."
|
||||
@@ -25,7 +23,16 @@ if [ -f /fs/microsd/params ]
|
||||
then
|
||||
param load /fs/microsd/params
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
@@ -48,6 +55,11 @@ sh /etc/init.d/rc.sensors
|
||||
# Start the commander.
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
@@ -57,11 +69,22 @@ attitude_estimator_ekf start
|
||||
echo "[init] starting PWM output"
|
||||
fmu mode_pwm
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
pwm -u 400 -m 0xff
|
||||
|
||||
#
|
||||
# Start attitude control
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
echo "[init] startup done, exiting"
|
||||
exit
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
blinkm systemstate
|
||||
fi
|
||||
+22
-7
@@ -1,8 +1,11 @@
|
||||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU+PX4IO
|
||||
#
|
||||
|
||||
# Disable USB and autostart
|
||||
# disable USB and autostart
|
||||
set USB no
|
||||
set MODE quad
|
||||
set MODE custom
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
@@ -18,6 +21,15 @@ if [ -f /fs/microsd/params ]
|
||||
then
|
||||
param load /fs/microsd/params
|
||||
fi
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
@@ -68,6 +80,11 @@ px4io start
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# Disable px4io topic limiting
|
||||
#
|
||||
px4io limit 200
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
@@ -88,20 +105,18 @@ attitude_estimator_ekf start
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
|
||||
pwm -u 400 -m 0xff
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
#sdlog start -s 4
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
||||
fi
|
||||
+19
-6
@@ -1,8 +1,11 @@
|
||||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU+PX4IO
|
||||
#
|
||||
|
||||
# Disable USB and autostart
|
||||
# disable USB and autostart
|
||||
set USB no
|
||||
set MODE camflyer
|
||||
set MODE custom
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
@@ -18,6 +21,15 @@ if [ -f /fs/microsd/params ]
|
||||
then
|
||||
param load /fs/microsd/params
|
||||
fi
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
@@ -68,6 +80,10 @@ px4io start
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# Set actuator limit to 100 Hz update (50 Hz PWM)
|
||||
px4io limit 100
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
@@ -93,15 +109,12 @@ control_demo start
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
#sdlog start -s 4
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
||||
@@ -0,0 +1,120 @@
|
||||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU+PX4IO
|
||||
#
|
||||
|
||||
# disable USB and autostart
|
||||
set USB no
|
||||
set MODE custom
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
#
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Load microSD params
|
||||
#
|
||||
echo "[init] loading microSD params"
|
||||
param select /fs/microsd/params
|
||||
if [ -f /fs/microsd/params ]
|
||||
then
|
||||
param load /fs/microsd/params
|
||||
fi
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set SYS_AUTOCONFIG 0
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
|
||||
#
|
||||
if [ -f /fs/microsd/px4io.bin ]
|
||||
then
|
||||
echo "PX4IO Firmware found. Checking Upgrade.."
|
||||
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
|
||||
then
|
||||
echo "No newer version, skipping upgrade."
|
||||
else
|
||||
echo "Loading /fs/microsd/px4io.bin"
|
||||
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
|
||||
then
|
||||
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
|
||||
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
|
||||
else
|
||||
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
|
||||
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start MAVLink (depends on orb)
|
||||
#
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the commander (depends on orb, mavlink)
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start PX4IO interface (depends on orb, commander)
|
||||
#
|
||||
px4io start
|
||||
|
||||
#
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# Set actuator limit to 100 Hz update (50 Hz PWM)
|
||||
px4io limit 100
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
kalman_demo start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
control_demo start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
blinkm systemstate
|
||||
fi
|
||||
@@ -24,6 +24,30 @@ else
|
||||
tone_alarm 2
|
||||
fi
|
||||
|
||||
#
|
||||
# Check if auto-setup from one of the standard scripts is wanted
|
||||
# SYS_AUTOSTART = 0 means no autostart (default)
|
||||
#
|
||||
if param compare SYS_AUTOSTART 1
|
||||
then
|
||||
sh /etc/init.d/rc.1_fmu_quad_x
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2
|
||||
then
|
||||
sh /etc/init.d/rc.2_fmu_io_quad_x
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 30
|
||||
then
|
||||
sh /etc/init.d/rc.30_fmu_io_camflyer
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 31
|
||||
then
|
||||
sh /etc/init.d/rc.31_fmu_io_phantom
|
||||
fi
|
||||
|
||||
#
|
||||
# Look for an init script on the microSD card.
|
||||
#
|
||||
|
||||
Reference in New Issue
Block a user