Updated and added full stops to comments and did some comment/whitespace formatting in the startup scripts.

This commit is contained in:
mcsauder 2018-07-26 18:18:53 -06:00 committed by Beat Küng
parent 13f2315314
commit 1fe526b8eb
10 changed files with 90 additions and 46 deletions

View File

@ -1,10 +1,15 @@
#!nsh
#
# Standard apps for rovers:
# att & pos estimator, rover steering control
# Attitude/Position estimator and rover steering control.
#
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
#
# Start the Attitude estimator.
#
ekf2 start
# disabled the start of steering control app due to use of offboard mode only
# rover_steering_control start
# rover_steering_control start.

View File

@ -1,26 +1,36 @@
#!nsh
#
# Standard defaults for rovers.
#
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
set VEHICLE_TYPE ugv
#
# This section can be enabled once tuning parameters for this particular
# rover model are known. It allows to configure default gains via the GUI
# rover model are known. It allows to configure default gains via the GUI.
#
if [ $AUTOCNF == yes ]
then
# PWM default value for "disarmed" mode
# this centers the steering and throttle, which means no motion
# for a rover
# PWM default value for "disarmed" mode.
# This centers the steering and throttle, which means
# no motion for a rover.
param set PWM_DISARMED 1500
# PWM range
# PWM range.
param set PWM_MIN 1200
param set PWM_MAX 1800
fi
#
# PWM Hz - 50 Hz is the normal rate in RC cars, higher rates
# may damage analog servos.
#
set PWM_RATE 50
# Enable servo output on pins 3 and 4 (steering and thrust)
# but also include 1+2 as they form together one output group
# and need to be set together.
#
# Enable servo output on pins 3 and 4 (steering and thrust) but also
# include 1+2 as they form one output group and need to be set together.
#
set PWM_OUT 1234

View File

@ -28,8 +28,10 @@ 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
@ -37,11 +39,16 @@ then
param set PWM_RATE 50
#
# FW takeoff acceleration can easily exceed ublox GPS 2G default.
#
param set GPS_UBX_DYNMODEL 8
fi
#
# This is the gimbal pass mixer.
#
set MIXER_AUX pass
set PWM_AUX_RATE 50
set PWM_AUX_OUT 1234

View File

@ -1,6 +1,6 @@
#!nsh
#
# Script to configure control interface
# Script to configure control interfaces.
#
#
# NOTE: environment variable references:

View File

@ -8,7 +8,10 @@
###############################################################################
# Begin Estimator Group Selection #
###############################################################################
#
# INAV (deprecated).
#
if param compare SYS_MC_EST_GROUP 0
then
echo "ERROR [init] Estimator INAV deprecated. Using EKF2"
@ -16,11 +19,15 @@ then
param save
fi
#
# LPE
#
if param compare SYS_MC_EST_GROUP 1
then
# Try to start LPE. If it fails, start EKF2 as a default
#
# Try to start LPE. If it fails, start EKF2 as a default.
# Unfortunately we do not build it on px4fmu-v2 due to a limited flash.
#
if attitude_estimator_q start
then
local_position_estimator start
@ -31,7 +38,9 @@ then
fi
fi
#
# EKF2
#
if param compare SYS_MC_EST_GROUP 2
then
ekf2 start

View File

@ -20,7 +20,10 @@ then
param set PWM_RATE 400
fi
#
# This is the gimbal pass mixer.
#
set MIXER_AUX pass
set PWM_AUX_RATE 50
set PWM_AUX_OUT 1234

View File

@ -2,6 +2,8 @@
#
# Standard startup script for sensor drivers.
#
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
###############################################################################
# Begin Setup for board specific configurations. #

View File

@ -10,7 +10,7 @@ set VEHICLE_TYPE ugv
if [ $AUTOCNF == yes ]
then
#
# Default parameters for UGVs
# Default parameters for UGVs.
#
param set MIS_LTRMIN_ALT 0.01
param set MIS_TAKEOFF_ALT 0.01
@ -18,20 +18,26 @@ then
param set NAV_DLL_ACT 0
param set NAV_ACC_RAD 2.0
# temporary
# Temporary.
param set NAV_FW_ALT_RAD 1000
fi
#
# Enable servo output on pins 3 and 4 (steering and thrust)
# but also include 1+2 as they form together one output group
# and need to be set together.
#
set PWM_OUT 1234
#
# PWM Hz - 50 Hz is the normal rate in RC cars, higher rates
# may damage analog servos.
#
set PWM_RATE 50
# 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

View File

@ -6,19 +6,19 @@
#
#
# Fixed wing setup
# Fixed wing setup.
#
if [ $VEHICLE_TYPE == fw ]
then
if [ $MIXER == none ]
then
# Set default mixer for fixed wing if not defined
# Set default mixer for fixed wing if not defined.
set MIXER AERT
fi
if [ $MAV_TYPE == none ]
then
# Use MAV_TYPE = 1 (fixed wing) if not defined
# Use MAV_TYPE = 1 (fixed wing) if not defined.
set MAV_TYPE 1
fi
@ -32,7 +32,7 @@ then
fi
#
# Multicopters setup
# Multicopter setup.
#
if [ $VEHICLE_TYPE == mc ]
then
@ -82,7 +82,7 @@ then
fi
fi
# Still no MAV_TYPE found
# Still no MAV_TYPE found.
if [ $MAV_TYPE == none ]
then
param set MAV_TYPE 2
@ -90,15 +90,15 @@ then
param set MAV_TYPE ${MAV_TYPE}
fi
# Load mixer and configure outputs
# Load mixer and configure outputs.
sh /etc/init.d/rc.interface
# Start standard multicopter apps
# Start standard multicopter apps.
sh /etc/init.d/rc.mc_apps
fi
#
# VTOL setup
# VTOL setup.
#
if [ $VEHICLE_TYPE == vtol ]
then
@ -109,7 +109,7 @@ then
if [ $MAV_TYPE == none ]
then
# Use mixer to detect vehicle type
# Use mixer to detect vehicle type.
if [ $MIXER == caipirinha_vtol ]
then
set MAV_TYPE 19
@ -124,7 +124,7 @@ then
fi
fi
# Still no MAV_TYPE found
# Still no MAV_TYPE found.
if [ $MAV_TYPE == none ]
then
echo "Unknown MAV_TYPE"
@ -133,10 +133,10 @@ then
param set MAV_TYPE ${MAV_TYPE}
fi
# Load mixer and configure outputs
# Load mixer and configure outputs.
sh /etc/init.d/rc.interface
# Start standard vtol apps
# Start standard vtol apps.
sh /etc/init.d/rc.vtol_apps
fi
@ -147,22 +147,22 @@ if [ $VEHICLE_TYPE == ugv ]
then
if [ $MIXER == none ]
then
# Set default mixer for UGV if not defined
# Set default mixer for UGV if not defined.
set MIXER ugv_generic
fi
if [ $MAV_TYPE == none ]
then
# Use MAV_TYPE = 10 (UGV) if not defined
# Use MAV_TYPE = 10 (UGV) if not defined.
set MAV_TYPE 10
fi
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs
# Load mixer and configure outputs.
sh /etc/init.d/rc.interface
# Start standard UGV apps
# Start standard UGV apps.
sh /etc/init.d/rc.ugv_apps
fi

View File

@ -46,7 +46,7 @@ set +e
#
#
# Set default paramter values
# Set default paramter values.
#
set AUX_MODE pwm
set DATAMAN_OPT ""
@ -157,12 +157,12 @@ else
uorb start
#
# Start tone driver.
# Start the tone_alarm driver.
#
tone_alarm start
#
# Play startup tone.
# Play the startup tone.
#
tune_control play -t 1
@ -224,15 +224,14 @@ else
#
if param compare SYS_AUTOCONFIG 1
then
# Wipe out params except RC*, flight modes and total flight time
# Wipe out params except RC*, flight modes and total flight time.
param reset_nostart RC* COM_FLTMODE* LND_FLIGHT_T_* TC_* CAL_ACC* CAL_GYRO*
set AUTOCNF yes
else
set AUTOCNF no
#
# Release 1.4.0 transitional support:
# set to old default if unconfigured,
# Release 1.4.0 transitional support: set to old default if unconfigured,
# this preserves the previous behaviour.
#
if param compare BAT_N_CELLS 0
@ -316,7 +315,7 @@ else
param set SYS_FMU_TASK 1
fi
# Disable safety switch by default on Pixracer and OmnibusF4SD
# Disable safety switch by default on Pixracer and OmnibusF4SD.
if ver hwcmp PX4FMU_V4 OMNIBUS_F4SD
then
param set CBRK_IO_SAFETY 22027
@ -351,7 +350,7 @@ else
if px4io start
then
# Try to safety px4 io so motor outputs dont go crazy.
# Try to safety px4 io so motor outputs don't go crazy.
if px4io safety_on
then
# success! no-op
@ -405,7 +404,7 @@ else
#
# Sensors System (start before Commander so Preflight checks are properly run).
# Commander Needs to be this early for in-air-restarts.
# Commander needs to be this early for in-air-restarts.
#
if param compare SYS_HITL 1
then
@ -527,12 +526,14 @@ else
echo "Addons script: ${FEXTRAS}"
sh $FEXTRAS
fi
#
# End of autostart.
#
fi
# There is no further script processing, so we can free some RAM
# XXX potentially unset all script variables.
#
# Unset all script parameters to free RAM.
#
unset AUX_MODE
unset DATAMAN_OPT
unset FAILSAFE
@ -568,6 +569,7 @@ unset PWM_MIN
unset USE_IO
unset VEHICLE_TYPE
#
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running.
#
mavlink boot_complete