Commit 9c355d28 authored by Lorenz Meier's avatar Lorenz Meier
Browse files

Merged beta into mavlink rework branch

parent ac77fe9c
......@@ -599,7 +599,7 @@ RECURSIVE = YES
# excluded from the INPUT source files. This way you can easily exclude a
# subdirectory from a directory tree whose root is specified with the INPUT tag.
EXCLUDE = ../src/modules/mathlib/CMSIS \
EXCLUDE = ../src/lib/mathlib/CMSIS \
../src/modules/attitude_estimator_ekf/codegen
# The EXCLUDE_SYMLINKS tag can be used select whether or not files or
......
#!nsh
#
# USB HIL start
# HILStar / X-Plane
#
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
#
echo "[HIL] HILStar starting.."
echo "HIL Rascal 110 starting.."
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
......@@ -40,48 +39,7 @@ then
param save
fi
# Allow USB some time to come up
sleep 1
# Tell MAVLink that this link is "fast"
mavlink start -b 230400 -d /dev/ttyACM0
# Create a fake HIL /dev/pwm_output interface
hil mode_pwm
#
# 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 we got an IO
#
if px4io start
then
echo "IO started"
else
fmu mode_serial
echo "FMU started"
fi
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
#
# Start the attitude estimator (depends on orb)
#
att_pos_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
fw_pos_control_l1 start
fw_att_control start
echo "[HIL] setup done, running"
set HIL yes
set VEHICLE_TYPE fw
set MIXER FMU_AERT
#!nsh
echo "[init] Team Blacksheep Discovery Quad"
#
# Load default params for this platform
# Team Blacksheep Discovery Quadcopter
#
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_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
# Maintainers: Simon Wilks <sjwilks@gmail.com>
#
# Force some key parameters to sane values
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
# Start and configure PX4IO or FMU interface
#
if px4io detect
if [ $DO_AUTOCONFIG == yes ]
then
# Start MAVLink (depends on orb)
mavlink start
usleep 5000
sh /etc/init.d/rc.io
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
usleep 5000
fmu mode_pwm
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
#
# Default parameters for this platform
#
param set MC_ATT_P 5.0
param set MC_ATT_I 0.0
param set MC_YAW_P 0.5
param set MC_YAW_I 0.15
param set MC_ATTRATE_P 0.17
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.006
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
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 rate -c 1234 -r 400
set VEHICLE_TYPE mc
set MIXER FMU_quad_w
#
# Set disarmed, min and max PWM signals
#
pwm disarmed -c 1234 -p 900
pwm min -c 1234 -p 1100
pwm max -c 1234 -p 1900
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
set PWM_OUTPUTS 1234
set PWM_RATE 400
#!nsh
echo "[init] 3DR Iris Quad"
#
# Load default params for this platform
# 3DR Iris Quadcopter
#
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.13
param set MC_ATT_D 0.0
param set MC_ATT_I 0.0
param set MC_ATT_P 9.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
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
# Force some key parameters to sane values
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
# Start and configure PX4IO or FMU interface
#
if px4io detect
if [ $DO_AUTOCONFIG == yes ]
then
# Start MAVLink (depends on orb)
mavlink start
usleep 5000
sh /etc/init.d/rc.io
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
usleep 5000
fmu mode_pwm
param set BAT_V_SCALING 0.0098
set EXIT_ON_END yes
#
# Default parameters for this platform
#
param set MC_ATT_P 9.0
param set MC_ATT_I 0.0
param set MC_YAW_P 0.5
param set MC_YAW_I 0.15
param set MC_ATTRATE_P 0.13
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MPC_TILT_MAX 1.0
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_MAX 5
param set MPC_XY_VEL_P 0.1
param set MPC_Z_P 1.0
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_MAX 3
param set MPC_Z_VEL_P 0.1
param set BAT_V_SCALING 0.00989
param set BAT_C_SCALING 0.0124
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 rate -c 1234 -r 400
set VEHICLE_TYPE mc
set MIXER FMU_quad_w
#
# Set disarmed, min and max PWM signals
#
pwm disarmed -c 1234 -p 900
pwm min -c 1234 -p 1050
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
set PWM_OUTPUTS 1234
set PWM_RATE 400
set PWM_DISARMED 900
set PWM_MIN 1000
set PWM_MAX 2000
#!nsh
#
# USB HIL start
#
echo "[HIL] HILS quadrotor starting.."
#
# 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.0
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_P 0.05
param set MC_ATT_D 0.0
param set MC_ATT_I 0.0
param set MC_ATT_P 3.0
param set MC_YAWPOS_D 0.0
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_P 2.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_P 0.05
param set NAV_TAKEOFF_ALT 3.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.5
param set MPC_THR_MIN 0.1
param set MPC_XY_D 0
param set MPC_XY_P 0.5
param set MPC_XY_VEL_D 0
param set MPC_XY_VEL_I 0
param set MPC_XY_VEL_MAX 3
param set MPC_XY_VEL_P 0.2
param set MPC_Z_D 0
param set MPC_Z_P 1
param set MPC_Z_VEL_D 0
param set MPC_Z_VEL_I 0.1
param set MPC_Z_VEL_MAX 2
param set MPC_Z_VEL_P 0.20
param save
fi
# Allow USB some time to come up
sleep 1
# Tell MAVLink that this link is "fast"
mavlink start -b 230400 -d /dev/ttyACM0
# Create a fake HIL /dev/pwm_output interface
hil mode_pwm
#
# 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 2
#
# Check if we got an IO
#
if px4io start
then
echo "IO started"
else
fmu mode_serial
echo "FMU started"
fi
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
#
# Start the attitude estimator (depends on orb)
#
att_pos_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Start position estimator
#
position_estimator_inav start
#
# Start attitude control
#
multirotor_att_control start
#
# Start position control
#
multirotor_pos_control start
echo "[HIL] setup done, running"
#!nsh
#
# HIL Quadcopter X
#
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set MC_ATT_P 7.0
param set MC_ATT_I 0.0
param set MC_YAW_P 2.0
param set MC_YAW_I 0.0
param set MC_ATTRATE_P 0.12
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_YAWRATE_P 0.3
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.005
param set MPC_TILT_MAX 1.0
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
param set MPC_XY_VEL_D 0.01
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_MAX 5
param set MPC_XY_VEL_P 0.1
param set MPC_Z_P 1.0
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_I 0.02
param set MPC_Z_VEL_MAX 3
param set MPC_Z_VEL_P 0.1
fi
set HIL yes
set VEHICLE_TYPE mc
set MIXER FMU_quad_x
#!nsh
#
# USB HIL start
# HIL Rascal 110 (Flightgear)
#
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
#
echo "[HIL] HILStar starting in state-HIL mode.."
echo "HIL Rascal 110 starting.."
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
......@@ -32,48 +31,15 @@ then
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 16
param set RC_SCALE_ROLL 1.0
param set RC_SCALE_PITCH 1.0
param set SYS_AUTOCONFIG 0
param save
fi
# Allow USB some time to come up
sleep 1
# Tell MAVLink that this link is "fast"
mavlink start -b 230400 -d /dev/ttyACM0
# Create a fake HIL /dev/pwm_output interface
hil mode_pwm
#
# 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 we got an IO
#
if px4io start
then
echo "IO started"
else
fmu mode_serial
echo "FMU started"
fi
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
#
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
fw_pos_control_l1 start
fw_att_control start
echo "[HIL] setup done, running"
set HIL yes
set VEHICLE_TYPE fw
set MIXER FMU_AERT
#!nsh
#
# USB HIL start
# HIL Quadcopter +
#
echo "[HIL] HILS quadrotor + starting.."
#
# 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.0
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_P 0.05
param set MC_ATT_D 0.0
param set MC_ATT_I 0.0
param set MC_ATT_P 3.0
param set MC_YAWPOS_D 0.0
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_P 2.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_P 0.05
param set NAV_TAKEOFF_ALT 3.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.5
param set MPC_THR_MIN 0.1
param set MPC_XY_D 0
param set MPC_XY_P 0.5
param set MPC_XY_VEL_D 0
param set MPC_XY_VEL_I 0
param set MPC_XY_VEL_MAX 3
param set MPC_XY_VEL_P 0.2
param set MPC_Z_D 0
param set MPC_Z_P 1
param set MPC_Z_VEL_D 0
param set MPC_Z_VEL_I 0.1
param set MPC_Z_VEL_MAX 2
param set MPC_Z_VEL_P 0.20
param save
fi
# Allow USB some time to come up
sleep 1
# Tell MAVLink that this link is "fast"
mavlink start -b 230400 -d /dev/ttyACM0
# Create a fake HIL /dev/pwm_output interface
hil mode_pwm
#
# 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 2
#
# Check if we got an IO
#
if px4io start
then
echo "IO started"
else
fmu mode_serial
echo "FMU started"
fi
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
#
# Start the attitude estimator (depends on orb)
#
att_pos_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
#
# Start position estimator
#
position_estimator_inav start
#
# Start attitude control
#
multirotor_att_control start
#
# Start position control
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
multirotor_pos_control start
echo "[HIL] setup done, running"
sh /etc/init.d/1001_rc_quad_x.hil
set MIXER FMU_quad_+
#!nsh
#
# USB HIL start
# HIL Rascal 110 (Flightgear)
#
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
#
echo "[HIL] HILStar starting.."
echo "HIL Rascal 110 starting.."