Add tap-v1 config

This commit is contained in:
Lorenz Meier
2016-07-06 13:32:10 +02:00
parent 7ed0eba50e
commit 332f669d9b
35 changed files with 4047 additions and 52 deletions
+18
View File
@@ -0,0 +1,18 @@
#!nsh
#
# @name Generic Quadrotor X config
#
# @type Quadrotor x
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
+19
View File
@@ -0,0 +1,19 @@
#!nsh
#
# @name Generic Hexarotor x geometry
#
# @type Hexarotor x
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
set MIXER hexa_x
# Need to set all 8 channels
set PWM_OUT 12345678
+20
View File
@@ -0,0 +1,20 @@
#!nsh
#
# Standard apps for fixed wing
#
#
# Start the attitude and position estimator
#
ekf2 start
#
# Start attitude controller
#
fw_att_control start
fw_pos_control_l1 start
#
# Start Land Detector
#
land_detector start fixedwing
+28
View File
@@ -0,0 +1,28 @@
#!nsh
set VEHICLE_TYPE fw
if [ $AUTOCNF == yes ]
then
#
# Default parameters for FW
#
param set RTL_RETURN_ALT 100
param set RTL_DESCEND_ALT 100
param set RTL_LAND_DELAY -1
param set NAV_ACC_RAD 50
param set PE_VELNE_NOISE 0.3
param set PE_VELD_NOISE 0.35
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.0
fi
# This is the gimbal pass mixer
set MIXER_AUX pass
set PWM_AUX_RATE 50
set PWM_AUX_OUT 1234
set PWM_AUX_DISARMED 1500
set PWM_AUX_MIN 1000
set PWM_AUX_MAX 2000
+83
View File
@@ -0,0 +1,83 @@
#!nsh
#
# Script to configure control interface
#
set SDCARD_MIXERS_PATH /fs/microsd/etc/mixers
if [ $MIXER != none -a $MIXER != skip ]
then
#
# Load main mixer
#
# Use the mixer file
set MIXER_FILE /etc/mixers/$MIXER.main.mix
set OUTPUT_DEV /dev/pwm_output0
if [ $OUTPUT_MODE == uavcan_esc ]
then
set OUTPUT_DEV /dev/uavcan/esc
fi
if mixer load $OUTPUT_DEV $MIXER_FILE
then
echo "INFO [init] Mixer: $MIXER_FILE on $OUTPUT_DEV"
else
echo "ERROR [init] Error loading mixer: $MIXER_FILE"
echo "ERROR:[init] Could not load mixer: $MIXER_FILE" >> $LOG_FILE
tone_alarm $TUNE_ERR
fi
unset MIXER_FILE
else
if [ $MIXER != skip ]
then
echo "ERROR [init] Mixer not defined"
echo "ERROR [init] Mixer not defined" >> $LOG_FILE
tone_alarm $TUNE_ERR
fi
fi
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
then
if [ $PWM_OUT != none ]
then
#
# Set PWM output frequency
#
if [ $PWM_RATE != none ]
then
pwm rate -c $PWM_OUT -r $PWM_RATE
fi
#
# Set disarmed, min and max PWM values
#
if [ $PWM_DISARMED != none ]
then
pwm disarmed -c $PWM_OUT -p $PWM_DISARMED
fi
if [ $PWM_MIN != none ]
then
pwm min -c $PWM_OUT -p $PWM_MIN
fi
if [ $PWM_MAX != none ]
then
pwm max -c $PWM_OUT -p $PWM_MAX
fi
fi
if [ $FAILSAFE != none ]
then
pwm failsafe -d $OUTPUT_DEV $FAILSAFE
fi
fi
unset PWM_OUT
unset PWM_RATE
unset PWM_MIN
unset PWM_MAX
unset FAILSAFE
unset OUTPUT_DEV
+39
View File
@@ -0,0 +1,39 @@
#!nsh
#
# Standard apps for multirotors:
# att & pos estimator, att & pos control.
#
#---------------------------------------
# Estimator group selction
#
# INAV
if param compare SYS_MC_EST_GROUP 0
then
attitude_estimator_q start
position_estimator_inav start
fi
# LPE
if param compare SYS_MC_EST_GROUP 1
then
attitude_estimator_q start
local_position_estimator start
fi
# EKF
if param compare SYS_MC_EST_GROUP 2
then
ekf2 start
fi
#---------------------------------------
mc_att_control start
mc_pos_control start
#
# Start Land Detector
#
land_detector start multicopter
+49
View File
@@ -0,0 +1,49 @@
#!nsh
set VEHICLE_TYPE mc
if [ $AUTOCNF == yes ]
then
param set PE_VELNE_NOISE 0.5
param set PE_VELD_NOISE 0.35
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.25
param set NAV_ACC_RAD 2.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set PWM_DISARMED 900
param set PWM_MIN 1075
param set PWM_MAX 1950
param set RTL_LAND_DELAY 0
fi
# set environment variables (!= parameters)
set PWM_RATE 400
# tell the mixer to use parameters for these instead
set PWM_DISARMED p:PWM_DISARMED
set PWM_MIN p:PWM_MIN
set PWM_MAX p:PWM_MAX
# This is the gimbal pass mixer
set MIXER_AUX pass
set PWM_AUX_RATE 50
set PWM_AUX_OUT 1234
set PWM_AUX_DISARMED 1500
set PWM_AUX_MIN 1000
set PWM_AUX_MAX 2000
# Transitional support: ensure suitable PWM min/max param values
if param compare PWM_MIN 1000
then
param set PWM_MIN 1075
fi
if param compare PWM_MAX 2000
then
param set PWM_MAX 1950
fi
if param compare PWM_DISARMED 0
then
param set PWM_DISARMED 900
fi
+46
View File
@@ -0,0 +1,46 @@
#!nsh
#
# Standard startup script for TAP v1 onboard sensor drivers.
#
if adc start
then
fi
# External I2C bus
if hmc5883 -C -T -X start
then
fi
if lis3mdl -R 2 start
then
fi
# Internal SPI bus is rotated 90 deg yaw
if hmc5883 -C -T -S -R 2 start
then
fi
# Internal SPI bus ICM-20608-G is rotated 90 deg yaw
if mpu6000 -R 2 -T 20608 start
then
fi
# Internal SPI bus mpu9250 is rotated 90 deg yaw
if mpu9250 -R 2 start
then
fi
if meas_airspeed start
then
fi
if sf10a start
then
fi
# Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
usleep 20000
if sensors start
then
fi
+44
View File
@@ -0,0 +1,44 @@
#!nsh
#
# Standard apps for vtol:
# att & pos estimator, att & pos control.
#
#
#---------------------------------------
# Estimator group selction
#
# INAV
if param compare SYS_MC_EST_GROUP 0
then
attitude_estimator_q start
position_estimator_inav start
fi
# LPE
if param compare SYS_MC_EST_GROUP 1
then
attitude_estimator_q start
local_position_estimator start
fi
# EKF
if param compare SYS_MC_EST_GROUP 2
then
ekf2 start
fi
#---------------------------------------
vtol_att_control start
mc_att_control start
mc_pos_control start
fw_att_control start
fw_pos_control_l1 start
#
# Start Land Detector
# Multicopter for now until we have something for VTOL
#
land_detector start vtol
+49
View File
@@ -0,0 +1,49 @@
#!nsh
set VEHICLE_TYPE vtol
if [ $AUTOCNF == yes ]
then
param set MC_ROLL_P 6.0
param set MC_PITCH_P 6.0
param set MC_YAW_P 4
param set PE_VELNE_NOISE 0.5
param set PE_VELD_NOISE 0.3
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.25
param set PE_ABIAS_PNOISE 0.0001
#
# Default parameters for mission and position handling
#
param set NAV_ACC_RAD 3
param set MPC_TKO_SPEED 1.0
param set MPC_LAND_SPEED 0.7
param set MPC_Z_VEL_MAX 1.5
param set MPC_XY_VEL_MAX 4.0
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2.0
param set RTL_LAND_DELAY 0
fi
# set environment variables (!= parameters)
set PWM_RATE 400
# tell the mixer to use parameters for these instead
set PWM_DISARMED p:PWM_DISARMED
set PWM_MIN p:PWM_MIN
set PWM_MAX p:PWM_MAX
# Transitional support: ensure suitable PWM min/max param values
if param compare PWM_MIN 1000
then
param set PWM_MIN 1075
fi
if param compare PWM_MAX 2000
then
param set PWM_MAX 1950
fi
if param compare PWM_DISARMED 0
then
param set PWM_DISARMED 900
fi
+482
View File
@@ -0,0 +1,482 @@
#!nsh
#
# PX4FMU startup script.
#
# NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS.
#
#
# Start CDC/ACM serial driver
#
sercon
#
# Default to auto-start mode.
#
set MODE autostart
set TUNE_ERR ML<<CP4CP4CP4CP4CP4
set LOG_FILE /fs/microsd/bootlog.txt
#
# Try to mount the microSD card.
#
# REBOOTWORK this needs to start after the flight control loop
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
# Start playing the startup tune
tone_alarm start
else
tone_alarm MBAGP
if mkfatfs /dev/mmcsd0
then
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "INFO [init] MicroSD card formatted"
else
echo "ERROR [init] Format failed"
tone_alarm MNBG
set LOG_FILE /dev/null
fi
else
set LOG_FILE /dev/null
fi
fi
#
# Look for an init script on the microSD card.
# Disable autostart if the script found.
#
set FRC /fs/microsd/etc/rc.txt
if [ -f $FRC ]
then
echo "INFO [init] Executing script: $FRC"
sh $FRC
set MODE custom
fi
unset FRC
if [ $MODE == autostart ]
then
#
# Start the ORB (first app to start)
#
uorb start
#
# Load parameters
#
set PARAM_FILE /fs/microsd/params
if mtd start
then
set PARAM_FILE /fs/mtd_params
fi
param select $PARAM_FILE
if param load
then
else
if param reset
then
fi
fi
#
# Start system state indicator
#
if rgbled start
then
fi
#
# Set AUTOCNF flag to use it in AUTOSTART scripts
#
if param compare SYS_AUTOCONFIG 1
then
# Wipe out params except RC*
param reset_nostart RC*
set AUTOCNF yes
else
set AUTOCNF no
fi
#
# Set default values
#
set VEHICLE_TYPE none
set MIXER none
set OUTPUT_MODE none
set PWM_OUT none
set PWM_RATE none
set PWM_DISARMED none
set PWM_MIN none
set PWM_MAX none
set FMU_MODE pwm
set MAVLINK_F default
set EXIT_ON_END no
set MAV_TYPE none
set FAILSAFE none
#
# Set parameters and env variables for selected AUTOSTART
#
if param compare SYS_AUTOSTART 0
then
echo "INFO [init] No autostart"
else
sh /etc/init.d/rc.autostart
fi
unset MODE
#
# If autoconfig parameter was set, reset it and save parameters
#
if [ $AUTOCNF == yes ]
then
param set SYS_AUTOCONFIG 0
param save
fi
unset AUTOCNF
#
# Set default output if not set
#
if [ $OUTPUT_MODE == none ]
then
if [ $USE_IO == yes ]
then
set OUTPUT_MODE io
else
set OUTPUT_MODE fmu
fi
fi
# waypoint storage
# REBOOTWORK this needs to start in parallel
if dataman start
then
fi
#
# Sensors System (start before Commander so Preflight checks are properly run)
#
sh /etc/init.d/rc.sensors
commander start
#
# Start CPU load monitor
#
load_mon start
#
# Start primary output
#
set TTYS1_BUSY no
#
# Check if UAVCAN is enabled, default to it for ESCs
#
if param greater UAVCAN_ENABLE 2
then
set OUTPUT_MODE uavcan_esc
fi
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
if [ $OUTPUT_MODE != none ]
then
if [ $OUTPUT_MODE == uavcan_esc ]
then
if param compare UAVCAN_ENABLE 0
then
echo "INFO [init] OVERRIDING UAVCAN_ENABLE = 1" >> $LOG_FILE
param set UAVCAN_ENABLE 1
fi
fi
if [ $OUTPUT_MODE == fmu ]
then
if fmu mode_$FMU_MODE
then
else
echo "ERR [init] FMU start failed" >> $LOG_FILE
tone_alarm $TUNE_ERR
fi
fi
if fmu mode_pwm4
then
else
echo "ERROR [init] FMU mode_$FMU_MODE start failed" >> $LOG_FILE
tone_alarm $TUNE_ERR
fi
fi
mavlink start -r 1200 -d /dev/ttyS1
#
# Starting stuff according to UAVCAN_ENABLE value
#
if param greater UAVCAN_ENABLE 0
then
if uavcan start
then
else
tone_alarm $TUNE_ERR
fi
fi
if param greater UAVCAN_ENABLE 1
then
if uavcan start fw
then
else
tone_alarm $TUNE_ERR
fi
fi
#
# Optional drivers
#
# Sensors on the PWM interface bank
if param compare SENS_EN_LL40LS 1
then
if pwm_input start
then
if ll40ls start pwm
then
fi
fi
fi
# sf0x lidar sensor
if param compare SENS_EN_SF0X 1
then
sf0x start
fi
# Start USB shell if no microSD present, MAVLink else
if [ $LOG_FILE == /dev/null ]
then
# Try to get an USB console
nshterm /dev/ttyACM0 &
else
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
fi
#
# Logging
#
if param compare SYS_LOGGER 0
then
if sdlog2 start -r 100 -a -b 9 -t
then
fi
else
if logger start -b 12
then
fi
fi
#
# Fixed wing setup
#
if [ $VEHICLE_TYPE == fw ]
then
echo "INFO [init] Fixedwing"
if [ $MIXER == none ]
then
# 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
set MAV_TYPE 1
fi
param set MAV_TYPE $MAV_TYPE
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
# Start standard fixedwing apps
sh /etc/init.d/rc.fw_apps
fi
#
# Multicopters setup
#
if [ $VEHICLE_TYPE == mc ]
then
echo "INFO [init] Multicopter"
if [ $MIXER == none ]
then
echo "INFO [init] Mixer undefined"
fi
if [ $MAV_TYPE == none ]
then
# Use mixer to detect vehicle type
if [ $MIXER == quad_x -o $MIXER == quad_+ ]
then
set MAV_TYPE 2
fi
if [ $MIXER == quad_w ]
then
set MAV_TYPE 2
fi
if [ $MIXER == quad_h ]
then
set MAV_TYPE 2
fi
if [ $MIXER == tri_y_yaw- -o $MIXER == tri_y_yaw+ ]
then
set MAV_TYPE 15
fi
if [ $MIXER == hexa_x -o $MIXER == hexa_+ ]
then
set MAV_TYPE 13
fi
if [ $MIXER == hexa_cox ]
then
set MAV_TYPE 13
fi
if [ $MIXER == octo_x -o $MIXER == octo_+ ]
then
set MAV_TYPE 14
fi
fi
# Still no MAV_TYPE found
if [ $MAV_TYPE == none ]
then
echo "WARN [init] Unknown MAV_TYPE"
param set MAV_TYPE 2
else
param set MAV_TYPE $MAV_TYPE
fi
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
# Start standard multicopter apps
sh /etc/init.d/rc.mc_apps
fi
#
# VTOL setup
#
if [ $VEHICLE_TYPE == vtol ]
then
echo "INFO [init] VTOL"
if [ $MIXER == none ]
then
echo "WARN [init] VTOL mixer undefined"
fi
if [ $MAV_TYPE == none ]
then
# Use mixer to detect vehicle type
if [ $MIXER == caipirinha_vtol ]
then
set MAV_TYPE 19
fi
if [ $MIXER == firefly6 ]
then
set MAV_TYPE 21
fi
if [ $MIXER == quad_x_pusher_vtol ]
then
set MAV_TYPE 22
fi
fi
# Still no MAV_TYPE found
if [ $MAV_TYPE == none ]
then
echo "WARN [init] Unknown MAV_TYPE"
param set MAV_TYPE 19
else
param set MAV_TYPE $MAV_TYPE
fi
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
# Start standard vtol apps
sh /etc/init.d/rc.vtol_apps
fi
#
# Rover setup
#
if [ $VEHICLE_TYPE == rover ]
then
# 10 is MAV_TYPE_GROUND_ROVER
set MAV_TYPE 10
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
# Start standard rover apps
sh /etc/init.d/rc.axialracing_ax10_apps
param set MAV_TYPE 10
fi
unset MIXER
unset MAV_TYPE
unset OUTPUT_MODE
#
# Start the navigator
#
navigator start
#
# Generic setup (autostart ID not found)
#
if [ $VEHICLE_TYPE == none ]
then
echo "WARN [init] No autostart ID found"
fi
# Start any custom addons
set FEXTRAS /fs/microsd/etc/extras.txt
if [ -f $FEXTRAS ]
then
echo "INFO [init] Addons script: $FEXTRAS"
sh $FEXTRAS
fi
unset FEXTRAS
# Run no SD alarm
if [ $LOG_FILE == /dev/null ]
then
# Play SOS
tone_alarm error
fi
# End of autostart
fi
# There is no further script processing, so we can free some RAM
# XXX potentially unset all script variables.
unset TUNE_ERR
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running
mavlink boot_complete
if [ $EXIT_ON_END == yes ]
then
echo "INFO [init] NSH exit"
exit
fi
unset EXIT_ON_END
+105
View File
@@ -0,0 +1,105 @@
## PX4 mixer definitions ##
Files in this directory implement example mixers that can be used as a basis
for customisation, or for general testing purposes.
For a detailed description of the mixing architecture and examples see:
http://px4.io/dev/mixing
### Syntax ###
Mixer definitions are text files; lines beginning with a single capital letter
followed by a colon are significant. All other lines are ignored, meaning that
explanatory text can be freely mixed with the definitions.
Each file may define more than one mixer; the allocation of mixers to actuators
is specific to the device reading the mixer definition, and the number of
actuator outputs generated by a mixer is specific to the mixer.
For example: each simple or null mixer is assigned to outputs 1 to x
in the order they appear in the mixer file.
A mixer begins with a line of the form
<tag>: <mixer arguments>
The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
multirotor mixer, etc.
#### Null Mixer ####
A null mixer consumes no controls and generates a single actuator output whose
value is always zero. Typically a null mixer is used as a placeholder in a
collection of mixers in order to achieve a specific pattern of actuator outputs.
The null mixer definition has the form:
Z:
#### Simple Mixer ####
A simple mixer combines zero or more control inputs into a single actuator
output. Inputs are scaled, and the mixing function sums the result before
applying an output scaler.
A simple mixer definition begins with:
M: <control count>
O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
If <control count> is zero, the sum is effectively zero and the mixer will
output a fixed value that is <offset> constrained by <lower limit> and <upper
limit>.
The second line defines the output scaler with scaler parameters as discussed
above. Whilst the calculations are performed as floating-point operations, the
values stored in the definition file are scaled by a factor of 10000; i.e. an
offset of -0.5 is encoded as -5000.
The definition continues with <control count> entries describing the control
inputs and their scaling, in the form:
S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
The <group> value identifies the control group from which the scaler will read,
and the <index> value an offset within that group. These values are specific to
the device reading the mixer definition.
When used to mix vehicle controls, mixer group zero is the vehicle attitude
control group, and index values zero through three are normally roll, pitch,
yaw and thrust respectively.
The remaining fields on the line configure the control scaler with parameters as
discussed above. Whilst the calculations are performed as floating-point
operations, the values stored in the definition file are scaled by a factor of
10000; i.e. an offset of -0.5 is encoded as -5000.
#### Multirotor Mixer ####
The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
into a set of actuator outputs intended to drive motor speed controllers.
The mixer definition is a single line of the form:
R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
The supported geometries include:
* 4x - quadrotor in X configuration
* 4+ - quadrotor in + configuration
* 6x - hexcopter in X configuration
* 6+ - hexcopter in + configuration
* 8x - octocopter in X configuration
* 8+ - octocopter in + configuration
Each of the roll, pitch and yaw scale values determine scaling of the roll,
pitch and yaw controls relative to the thrust control. Whilst the calculations
are performed as floating-point operations, the values stored in the definition
file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
range -1.0 to 1.0.
In the case where an actuator saturates, all actuator values are rescaled so that
the saturating actuator is limited to 1.0.
+3
View File
@@ -0,0 +1,3 @@
# Hexa X
R: 6x 10000 10000 10000 0
+7
View File
@@ -0,0 +1,7 @@
R: 4x 10000 10000 10000 0
M: 1
O: 10000 10000 0 -10000 10000
S: 3 5 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 3 6 10000 10000 0 -10000 10000