mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Format and comment fw, mc, vtol, and ugv vehicle apps and default startup scripts.
This commit is contained in:
parent
8537863848
commit
2512f6e30e
@ -2,6 +2,8 @@
|
||||
#
|
||||
# Standard apps for fixed wing
|
||||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
# LPE
|
||||
if param compare SYS_MC_EST_GROUP 1
|
||||
@ -12,22 +14,22 @@ then
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
# Start the attitude and position estimator.
|
||||
#
|
||||
ekf2 start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
# Start attitude controller.
|
||||
#
|
||||
fw_att_control start
|
||||
fw_pos_control_l1 start
|
||||
|
||||
#
|
||||
# Start Land Detector
|
||||
# Start Land Detector.
|
||||
#
|
||||
land_detector start fixedwing
|
||||
|
||||
#
|
||||
# Start Wind and Airspeed Scale Estimator
|
||||
# Start Wind and Airspeed Scale Estimator.
|
||||
#
|
||||
#wind_estimator start
|
||||
|
||||
@ -1,11 +1,16 @@
|
||||
#!nsh
|
||||
#
|
||||
# Fixed wing default parameters
|
||||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for FW
|
||||
# Default parameters for fixed wing uavs.
|
||||
#
|
||||
param set COM_POS_FS_DELAY 5
|
||||
param set COM_POS_FS_EPH 25
|
||||
@ -23,8 +28,8 @@ then
|
||||
param set RTL_DESCEND_ALT 100
|
||||
param set RTL_LAND_DELAY -1
|
||||
|
||||
# FW uses L1 distance for acceptance radius
|
||||
# set a smaller NAV_ACC_RAD for vertical acceptance distance
|
||||
# FW uses L1 distance for acceptance radius,
|
||||
# set a smaller NAV_ACC_RAD for vertical acceptance distance.
|
||||
param set NAV_ACC_RAD 10
|
||||
|
||||
param set MIS_LTRMIN_ALT 25
|
||||
@ -32,11 +37,11 @@ then
|
||||
|
||||
param set PWM_RATE 50
|
||||
|
||||
# FW takeoff acceleration can easily exceed ublox GPS 2G default
|
||||
# FW takeoff acceleration can easily exceed ublox GPS 2G default.
|
||||
param set GPS_UBX_DYNMODEL 8
|
||||
fi
|
||||
|
||||
# This is the gimbal pass mixer
|
||||
# This is the gimbal pass mixer.
|
||||
set MIXER_AUX pass
|
||||
set PWM_AUX_RATE 50
|
||||
set PWM_AUX_OUT 1234
|
||||
|
||||
@ -1,14 +1,14 @@
|
||||
#!nsh
|
||||
#
|
||||
# Standard apps for multirotors:
|
||||
# att & pos estimator, att & pos control.
|
||||
# Standard apps for multirotors. Attitude/Position estimator, Attitude/Position control.
|
||||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
|
||||
#---------------------------------------
|
||||
# Estimator group selction
|
||||
#
|
||||
# INAV (deprecated)
|
||||
###############################################################################
|
||||
# Begin Estimator Group Selection #
|
||||
###############################################################################
|
||||
# INAV (deprecated).
|
||||
if param compare SYS_MC_EST_GROUP 0
|
||||
then
|
||||
echo "ERROR [init] Estimator INAV deprecated. Using EKF2"
|
||||
@ -31,18 +31,26 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
# EKF
|
||||
# EKF2
|
||||
if param compare SYS_MC_EST_GROUP 2
|
||||
then
|
||||
ekf2 start
|
||||
fi
|
||||
#---------------------------------------
|
||||
###############################################################################
|
||||
# End Estimator Group Selection #
|
||||
###############################################################################
|
||||
|
||||
#
|
||||
# Start Multicopter Attitude Controller.
|
||||
#
|
||||
mc_att_control start
|
||||
|
||||
#
|
||||
# Start Multicopter Position Controller.
|
||||
#
|
||||
mc_pos_control start
|
||||
|
||||
#
|
||||
# Start Land Detector
|
||||
# Start Multicopter Land Detector.
|
||||
#
|
||||
land_detector start multicopter
|
||||
|
||||
@ -1,20 +1,26 @@
|
||||
#!nsh
|
||||
#
|
||||
# Multicopter default parameters.
|
||||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set NAV_ACC_RAD 2.0
|
||||
|
||||
param set RTL_RETURN_ALT 30.0
|
||||
param set RTL_DESCEND_ALT 10.0
|
||||
param set PWM_MIN 1075
|
||||
param set PWM_MAX 1950
|
||||
param set PWM_RATE 400
|
||||
|
||||
param set RTL_LAND_DELAY 0
|
||||
|
||||
param set PWM_MAX 1950
|
||||
param set PWM_MIN 1075
|
||||
param set PWM_RATE 400
|
||||
fi
|
||||
|
||||
# This is the gimbal pass mixer
|
||||
# This is the gimbal pass mixer.
|
||||
set MIXER_AUX pass
|
||||
set PWM_AUX_RATE 50
|
||||
set PWM_AUX_OUT 1234
|
||||
|
||||
@ -1,10 +1,12 @@
|
||||
#!nsh
|
||||
#
|
||||
# Standard apps for unmanned ground vehicles (UGV)
|
||||
# Standard apps for unmanned ground vehicles (UGV).
|
||||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
# Start the attitude and position estimator.
|
||||
#
|
||||
ekf2 start
|
||||
#attitude_estimator_q start
|
||||
@ -12,13 +14,13 @@ ekf2 start
|
||||
|
||||
|
||||
#
|
||||
# Start attitude controllers
|
||||
# Start attitude controllers.
|
||||
#
|
||||
gnd_att_control start
|
||||
gnd_pos_control start
|
||||
|
||||
|
||||
#
|
||||
# Start Land Detector
|
||||
# Start Land Detector.
|
||||
#
|
||||
land_detector start ugv
|
||||
|
||||
@ -1,4 +1,9 @@
|
||||
#!nsh
|
||||
#
|
||||
# UGV default parameters.
|
||||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
set VEHICLE_TYPE ugv
|
||||
|
||||
@ -7,14 +12,14 @@ then
|
||||
#
|
||||
# Default parameters for UGVs
|
||||
#
|
||||
param set MIS_LTRMIN_ALT 0.01
|
||||
param set MIS_TAKEOFF_ALT 0.01
|
||||
|
||||
param set NAV_DLL_ACT 0
|
||||
param set NAV_ACC_RAD 2.0
|
||||
|
||||
# temporary
|
||||
param set NAV_FW_ALT_RAD 1000
|
||||
|
||||
param set MIS_LTRMIN_ALT 0.01
|
||||
param set MIS_TAKEOFF_ALT 0.01
|
||||
fi
|
||||
|
||||
# Enable servo output on pins 3 and 4 (steering and thrust)
|
||||
|
||||
@ -1,14 +1,14 @@
|
||||
#!nsh
|
||||
#
|
||||
# Standard apps for vtol:
|
||||
# att & pos estimator, att & pos control.
|
||||
# Standard apps for vtol: Attitude/Position estimator, Attitude/Position control.
|
||||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
###############################################################################
|
||||
# Begin Estimator group selection #
|
||||
###############################################################################
|
||||
|
||||
#---------------------------------------
|
||||
# Estimator group selction
|
||||
#
|
||||
# INAV (deprecated)
|
||||
if param compare SYS_MC_EST_GROUP 0
|
||||
then
|
||||
@ -37,7 +37,10 @@ if param compare SYS_MC_EST_GROUP 2
|
||||
then
|
||||
ekf2 start
|
||||
fi
|
||||
#---------------------------------------
|
||||
|
||||
###############################################################################
|
||||
# End Estimator group selection #
|
||||
###############################################################################
|
||||
|
||||
|
||||
vtol_att_control start
|
||||
|
||||
@ -1,4 +1,9 @@
|
||||
#!nsh
|
||||
#
|
||||
# VTOL default parameters.
|
||||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
set VEHICLE_TYPE vtol
|
||||
|
||||
@ -18,5 +23,5 @@ then
|
||||
param set RTL_LAND_DELAY 0
|
||||
fi
|
||||
|
||||
# set environment variables (!= parameters)
|
||||
# Set environment variables (!= parameters)
|
||||
set PWM_RATE 400
|
||||
|
||||
@ -129,10 +129,14 @@ then
|
||||
#
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Start tone driver
|
||||
#
|
||||
tone_alarm start
|
||||
|
||||
#
|
||||
# play startup tone
|
||||
#
|
||||
tune_control play -t 1
|
||||
|
||||
#
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user