mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 20:28:37 +08:00
ROMFS reshuffling / cleanup, in sync with QGC
This commit is contained in:
@@ -1,64 +0,0 @@
|
|||||||
#!nsh
|
|
||||||
|
|
||||||
echo "[init] 01_fmu_quad_x: PX4FMU Quad X with PWM outputs"
|
|
||||||
|
|
||||||
#
|
|
||||||
# Load default params for this platform
|
|
||||||
#
|
|
||||||
if param compare SYS_AUTOCONFIG 1
|
|
||||||
then
|
|
||||||
# Set all params here, then disable autoconfig
|
|
||||||
param set MC_ATTRATE_P 0.14
|
|
||||||
param set MC_ATTRATE_I 0
|
|
||||||
param set MC_ATTRATE_D 0.006
|
|
||||||
param set MC_ATT_P 5.5
|
|
||||||
param set MC_ATT_I 0
|
|
||||||
param set MC_ATT_D 0
|
|
||||||
param set MC_YAWPOS_D 0
|
|
||||||
param set MC_YAWPOS_I 0
|
|
||||||
param set MC_YAWPOS_P 0.6
|
|
||||||
param set MC_YAWRATE_D 0
|
|
||||||
param set MC_YAWRATE_I 0
|
|
||||||
param set MC_YAWRATE_P 0.08
|
|
||||||
param set RC_SCALE_PITCH 1
|
|
||||||
param set RC_SCALE_ROLL 1
|
|
||||||
param set RC_SCALE_YAW 3
|
|
||||||
|
|
||||||
param set SYS_AUTOCONFIG 0
|
|
||||||
param save
|
|
||||||
fi
|
|
||||||
|
|
||||||
#
|
|
||||||
# Force some key parameters to sane values
|
|
||||||
# MAV_TYPE 2 = quadrotor
|
|
||||||
#
|
|
||||||
param set MAV_TYPE 2
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start MAVLink
|
|
||||||
#
|
|
||||||
mavlink start -d /dev/ttyS0 -b 57600
|
|
||||||
usleep 5000
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start PWM output
|
|
||||||
#
|
|
||||||
fmu mode_pwm
|
|
||||||
|
|
||||||
#
|
|
||||||
# Load mixer
|
|
||||||
#
|
|
||||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
|
||||||
|
|
||||||
#
|
|
||||||
# Set PWM output frequency
|
|
||||||
#
|
|
||||||
pwm -u 400 -m 0xff
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start common for all multirotors apps
|
|
||||||
#
|
|
||||||
sh /etc/init.d/rc.multirotor
|
|
||||||
|
|
||||||
# Exit, because /dev/ttyS0 is needed for MAVLink
|
|
||||||
exit
|
|
||||||
@@ -1,47 +0,0 @@
|
|||||||
#!nsh
|
|
||||||
|
|
||||||
echo "[init] 02_io_quad_x: PX4FMU+PX4IO Quad X with PWM outputs"
|
|
||||||
|
|
||||||
#
|
|
||||||
# Load default params for this platform
|
|
||||||
#
|
|
||||||
if param compare SYS_AUTOCONFIG 1
|
|
||||||
then
|
|
||||||
# Set all params here, then disable autoconfig
|
|
||||||
# TODO
|
|
||||||
|
|
||||||
param set SYS_AUTOCONFIG 0
|
|
||||||
param save /fs/microsd/params
|
|
||||||
fi
|
|
||||||
|
|
||||||
#
|
|
||||||
# Force some key parameters to sane values
|
|
||||||
# MAV_TYPE 2 = quadrotor
|
|
||||||
#
|
|
||||||
param set MAV_TYPE 2
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start MAVLink
|
|
||||||
#
|
|
||||||
mavlink start -d /dev/ttyS1 -b 57600
|
|
||||||
usleep 5000
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start and configure PX4IO interface
|
|
||||||
#
|
|
||||||
sh /etc/init.d/rc.io
|
|
||||||
|
|
||||||
#
|
|
||||||
# Load mixer
|
|
||||||
#
|
|
||||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
|
||||||
|
|
||||||
#
|
|
||||||
# Set PWM output frequency
|
|
||||||
#
|
|
||||||
pwm -u 400 -m 0xff
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start common for all multirotors apps
|
|
||||||
#
|
|
||||||
sh /etc/init.d/rc.multirotor
|
|
||||||
@@ -0,0 +1,68 @@
|
|||||||
|
#!nsh
|
||||||
|
|
||||||
|
echo "[init] Multiplex Easystar"
|
||||||
|
|
||||||
|
#
|
||||||
|
# Load default params for this platform
|
||||||
|
#
|
||||||
|
if param compare SYS_AUTOCONFIG 1
|
||||||
|
then
|
||||||
|
# Set all params here, then disable autoconfig
|
||||||
|
# TODO
|
||||||
|
|
||||||
|
param set SYS_AUTOCONFIG 0
|
||||||
|
param save
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Force some key parameters to sane values
|
||||||
|
# MAV_TYPE 1 = fixed wing
|
||||||
|
#
|
||||||
|
param set MAV_TYPE 1
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start MAVLink (depends on orb)
|
||||||
|
#
|
||||||
|
mavlink start -d /dev/ttyS1 -b 57600
|
||||||
|
usleep 5000
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start and configure PX4IO interface
|
||||||
|
#
|
||||||
|
sh /etc/init.d/rc.io
|
||||||
|
|
||||||
|
#
|
||||||
|
# Set actuator limit to 100 Hz update (50 Hz PWM)
|
||||||
|
px4io limit 100
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start the commander
|
||||||
|
#
|
||||||
|
commander start
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start the sensors
|
||||||
|
#
|
||||||
|
sh /etc/init.d/rc.sensors
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start logging (depends on sensors)
|
||||||
|
#
|
||||||
|
sh /etc/init.d/rc.logging
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start GPS interface
|
||||||
|
#
|
||||||
|
gps start
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start the attitude and position estimator
|
||||||
|
#
|
||||||
|
att_pos_estimator_ekf start
|
||||||
|
|
||||||
|
#
|
||||||
|
# Load mixer and start controllers (depends on px4io)
|
||||||
|
#
|
||||||
|
mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
|
||||||
|
fw_att_control start
|
||||||
|
fw_pos_control_l1 start
|
||||||
@@ -0,0 +1,78 @@
|
|||||||
|
#!nsh
|
||||||
|
|
||||||
|
echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
|
||||||
|
|
||||||
|
#
|
||||||
|
# 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
|
||||||
|
|
||||||
|
param set MC_ATTRATE_D 0.004
|
||||||
|
param set MC_ATTRATE_I 0.0
|
||||||
|
param set MC_ATTRATE_P 0.12
|
||||||
|
param set MC_ATT_D 0.0
|
||||||
|
param set MC_ATT_I 0.0
|
||||||
|
param set MC_ATT_P 7.0
|
||||||
|
param set MC_RCLOSS_THR 0.0
|
||||||
|
param set MC_YAWPOS_D 0.0
|
||||||
|
param set MC_YAWPOS_I 0.0
|
||||||
|
param set MC_YAWPOS_P 2.0
|
||||||
|
param set MC_YAWRATE_D 0.005
|
||||||
|
param set MC_YAWRATE_I 0.2
|
||||||
|
param set MC_YAWRATE_P 0.3
|
||||||
|
|
||||||
|
param save
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Force some key parameters to sane values
|
||||||
|
# MAV_TYPE 2 = quadrotor
|
||||||
|
#
|
||||||
|
param set MAV_TYPE 2
|
||||||
|
|
||||||
|
set EXIT_ON_END no
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start and configure PX4IO or FMU interface
|
||||||
|
#
|
||||||
|
if px4io detect
|
||||||
|
then
|
||||||
|
# Start MAVLink (depends on orb)
|
||||||
|
mavlink start
|
||||||
|
usleep 5000
|
||||||
|
|
||||||
|
sh /etc/init.d/rc.io
|
||||||
|
# Set PWM values for DJI ESCs
|
||||||
|
px4io idle 900 900 900 900
|
||||||
|
px4io min 1200 1200 1200 1200
|
||||||
|
px4io max 1800 1800 1800 1800
|
||||||
|
else
|
||||||
|
# Start MAVLink (on UART1 / ttyS0)
|
||||||
|
mavlink start -d /dev/ttyS0
|
||||||
|
usleep 5000
|
||||||
|
fmu mode_pwm
|
||||||
|
set EXIT_ON_END yes
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Load mixer
|
||||||
|
#
|
||||||
|
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||||
|
|
||||||
|
#
|
||||||
|
# Set PWM output frequency
|
||||||
|
#
|
||||||
|
pwm -u 400 -m 0xff
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start common for all multirotors apps
|
||||||
|
#
|
||||||
|
sh /etc/init.d/rc.multirotor
|
||||||
|
|
||||||
|
if [ $EXIT_ON_END == yes ]
|
||||||
|
then
|
||||||
|
exit
|
||||||
|
fi
|
||||||
@@ -0,0 +1,78 @@
|
|||||||
|
#!nsh
|
||||||
|
|
||||||
|
echo "[init] Team Blacksheep Discovery Quad"
|
||||||
|
|
||||||
|
#
|
||||||
|
# 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
|
||||||
|
|
||||||
|
param set MC_ATTRATE_D 0.006
|
||||||
|
param set MC_ATTRATE_I 0.0
|
||||||
|
param set MC_ATTRATE_P 0.17
|
||||||
|
param set MC_ATT_D 0.0
|
||||||
|
param set MC_ATT_I 0.0
|
||||||
|
param set MC_ATT_P 5.0
|
||||||
|
param set MC_RCLOSS_THR 0.0
|
||||||
|
param set MC_YAWPOS_D 0.0
|
||||||
|
param set MC_YAWPOS_I 0.15
|
||||||
|
param set MC_YAWPOS_P 0.5
|
||||||
|
param set MC_YAWRATE_D 0.0
|
||||||
|
param set MC_YAWRATE_I 0.0
|
||||||
|
param set MC_YAWRATE_P 0.2
|
||||||
|
|
||||||
|
param save
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Force some key parameters to sane values
|
||||||
|
# MAV_TYPE 2 = quadrotor
|
||||||
|
#
|
||||||
|
param set MAV_TYPE 2
|
||||||
|
|
||||||
|
set EXIT_ON_END no
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start and configure PX4IO or FMU interface
|
||||||
|
#
|
||||||
|
if px4io detect
|
||||||
|
then
|
||||||
|
# Start MAVLink (depends on orb)
|
||||||
|
mavlink start
|
||||||
|
usleep 5000
|
||||||
|
|
||||||
|
sh /etc/init.d/rc.io
|
||||||
|
# Set PWM values for DJI ESCs
|
||||||
|
px4io idle 900 900 900 900
|
||||||
|
px4io min 1200 1200 1200 1200
|
||||||
|
px4io max 1800 1800 1800 1800
|
||||||
|
else
|
||||||
|
# Start MAVLink (on UART1 / ttyS0)
|
||||||
|
mavlink start -d /dev/ttyS0
|
||||||
|
usleep 5000
|
||||||
|
fmu mode_pwm
|
||||||
|
set EXIT_ON_END yes
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Load the mixer for a quad with wide arms
|
||||||
|
#
|
||||||
|
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
||||||
|
|
||||||
|
#
|
||||||
|
# Set PWM output frequency
|
||||||
|
#
|
||||||
|
pwm -u 400 -m 0xff
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start common for all multirotors apps
|
||||||
|
#
|
||||||
|
sh /etc/init.d/rc.multirotor
|
||||||
|
|
||||||
|
if [ $EXIT_ON_END == yes ]
|
||||||
|
then
|
||||||
|
exit
|
||||||
|
fi
|
||||||
@@ -1,6 +1,6 @@
|
|||||||
#!nsh
|
#!nsh
|
||||||
|
|
||||||
echo "[init] 15_io_tbs: PX4FMU+PX4IO on a Team Blacksheep Discovery quad"
|
echo "[init] 3DR Iris Quad"
|
||||||
|
|
||||||
#
|
#
|
||||||
# Load default params for this platform
|
# Load default params for this platform
|
||||||
@@ -33,23 +33,29 @@ fi
|
|||||||
#
|
#
|
||||||
param set MAV_TYPE 2
|
param set MAV_TYPE 2
|
||||||
|
|
||||||
|
set EXIT_ON_END no
|
||||||
|
|
||||||
#
|
#
|
||||||
|
# Start and configure PX4IO or FMU interface
|
||||||
|
#
|
||||||
|
if px4io detect
|
||||||
|
then
|
||||||
# Start MAVLink (depends on orb)
|
# Start MAVLink (depends on orb)
|
||||||
#
|
|
||||||
mavlink start
|
mavlink start
|
||||||
usleep 5000
|
usleep 5000
|
||||||
|
|
||||||
#
|
|
||||||
# Start and configure PX4IO interface
|
|
||||||
#
|
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
|
|
||||||
#
|
|
||||||
# Set PWM values for DJI ESCs
|
# Set PWM values for DJI ESCs
|
||||||
#
|
|
||||||
px4io idle 900 900 900 900
|
px4io idle 900 900 900 900
|
||||||
px4io min 1180 1180 1180 1180
|
px4io min 1200 1200 1200 1200
|
||||||
px4io max 1800 1800 1800 1800
|
px4io max 1800 1800 1800 1800
|
||||||
|
else
|
||||||
|
# Start MAVLink (on UART1 / ttyS0)
|
||||||
|
mavlink start -d /dev/ttyS0
|
||||||
|
usleep 5000
|
||||||
|
fmu mode_pwm
|
||||||
|
set EXIT_ON_END yes
|
||||||
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
# Load the mixer for a quad with wide arms
|
# Load the mixer for a quad with wide arms
|
||||||
@@ -65,3 +71,8 @@ pwm -u 400 -m 0xff
|
|||||||
# Start common for all multirotors apps
|
# Start common for all multirotors apps
|
||||||
#
|
#
|
||||||
sh /etc/init.d/rc.multirotor
|
sh /etc/init.d/rc.multirotor
|
||||||
|
|
||||||
|
if [ $EXIT_ON_END == yes ]
|
||||||
|
then
|
||||||
|
exit
|
||||||
|
fi
|
||||||
@@ -61,12 +61,13 @@ sh /etc/init.d/rc.logging
|
|||||||
gps start
|
gps start
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start the attitude estimator (depends on orb)
|
# Start the attitude and position estimator
|
||||||
#
|
#
|
||||||
kalman_demo start
|
att_pos_estimator_ekf start
|
||||||
|
|
||||||
#
|
#
|
||||||
# Load mixer and start controllers (depends on px4io)
|
# Load mixer and start controllers (depends on px4io)
|
||||||
#
|
#
|
||||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||||
fw_att_control start
|
fw_att_control start
|
||||||
|
fw_pos_control_l1 start
|
||||||
|
|||||||
@@ -56,12 +56,13 @@ sh /etc/init.d/rc.logging
|
|||||||
gps start
|
gps start
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start the attitude estimator
|
# Start the attitude and position estimator
|
||||||
#
|
#
|
||||||
kalman_demo start
|
att_pos_estimator_ekf start
|
||||||
|
|
||||||
#
|
#
|
||||||
# Load mixer and start controllers (depends on px4io)
|
# Load mixer and start controllers (depends on px4io)
|
||||||
#
|
#
|
||||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||||
fw_att_control start
|
fw_att_control start
|
||||||
|
fw_pos_control_l1 start
|
||||||
|
|||||||
@@ -125,17 +125,6 @@ then
|
|||||||
# Check if auto-setup from one of the standard scripts is wanted
|
# Check if auto-setup from one of the standard scripts is wanted
|
||||||
# SYS_AUTOSTART = 0 means no autostart (default)
|
# SYS_AUTOSTART = 0 means no autostart (default)
|
||||||
#
|
#
|
||||||
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
|
if param compare SYS_AUTOSTART 8
|
||||||
then
|
then
|
||||||
@@ -151,13 +140,25 @@ then
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 10
|
if param compare SYS_AUTOSTART 10
|
||||||
then
|
then
|
||||||
sh /etc/init.d/10_io_f330
|
sh /etc/init.d/10_dji_f330
|
||||||
|
set MODE custom
|
||||||
|
fi
|
||||||
|
|
||||||
|
if param compare SYS_AUTOSTART 11
|
||||||
|
then
|
||||||
|
sh /etc/init.d/11_dji_f450
|
||||||
set MODE custom
|
set MODE custom
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if param compare SYS_AUTOSTART 15
|
if param compare SYS_AUTOSTART 15
|
||||||
then
|
then
|
||||||
sh /etc/init.d/15_io_tbs
|
sh /etc/init.d/15_tbs_discovery
|
||||||
|
set MODE custom
|
||||||
|
fi
|
||||||
|
|
||||||
|
if param compare SYS_AUTOSTART 16
|
||||||
|
then
|
||||||
|
sh /etc/init.d/16_3dr_iris
|
||||||
set MODE custom
|
set MODE custom
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user