Merge branch 'master' of github.com:PX4/Firmware into rssi

This commit is contained in:
Lorenz Meier 2014-01-23 07:49:18 +01:00
commit ba19a1ba15
48 changed files with 1403 additions and 2122 deletions

View File

@ -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

View File

@ -1,74 +1,31 @@
#!nsh
echo "[init] Team Blacksheep Discovery Quad"
#
# Load default params for this platform
# Team Blacksheep Discovery Quadcopter
#
if param compare SYS_AUTOCONFIG 1
# Maintainers: Simon Wilks <sjwilks@gmail.com>
#
if [ $DO_AUTOCONFIG == yes ]
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
#
# Default parameters for this platform
#
param set MC_ATT_P 5.0
param set MC_YAWPOS_D 0.0
param set MC_YAWPOS_I 0.15
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_ATTRATE_P 0.17
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.006
param set MC_YAWPOS_P 0.5
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_I 0.0
param set MC_YAWPOS_I 0.15
param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
param save
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
fi
#
# Force some key parameters to sane values
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
set VEHICLE_TYPE mc
set MIXER FMU_quad_w
#
# 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
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
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 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

View File

@ -1,73 +1,53 @@
#!nsh
echo "[init] 3DR Iris Quad"
#
# Load default params for this platform
# 3DR Iris Quadcopter
#
if param compare SYS_AUTOCONFIG 1
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
if [ $DO_AUTOCONFIG == yes ]
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
#
# Default parameters for this platform
#
param set MC_ATT_P 9.0
param set MC_YAWPOS_D 0.0
param set MC_YAWPOS_I 0.15
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_ATTRATE_P 0.13
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_YAWPOS_P 0.5
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_I 0.0
param set MC_YAWPOS_I 0.15
param set MC_YAWPOS_D 0.0
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 0.5
param set MPC_THR_MAX 0.8
param set MPC_THR_MIN 0.2
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
param set BAT_V_SCALING 0.00989
param set BAT_C_SCALING 0.0124
fi
#
# Force some key parameters to sane values
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
set VEHICLE_TYPE mc
set MIXER FMU_quad_w
#
# 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
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
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 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

View File

@ -1,105 +0,0 @@
#!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"

View File

@ -0,0 +1,46 @@
#!nsh
#
# HIL Quadcopter X
#
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set MC_ATTRATE_P 0.12
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_ATT_P 7.0
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_YAWPOS_P 2.0
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_D 0.0
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 0.5
param set MPC_THR_MAX 0.8
param set MPC_THR_MIN 0.2
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
fi
set HIL yes
set VEHICLE_TYPE mc
set MIXER FMU_quad_x

View File

@ -1,105 +1,46 @@
#!nsh
#
# USB HIL start
# HIL Quadcopter +
#
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
echo "[HIL] HILS quadrotor + 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
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
#
# Default parameters for this platform
#
param set MC_ATTRATE_P 0.12
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_D 0.004
param set MC_ATT_P 7.0
param set MC_ATT_I 0.0
param set MC_ATT_D 0.0
param set MC_YAWPOS_P 2.0
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_D 0.0
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 0.5
param set MPC_THR_MAX 0.8
param set MPC_THR_MIN 0.2
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
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
#
multirotor_pos_control start
echo "[HIL] setup done, running"
set HIL yes
set VEHICLE_TYPE mc
set MIXER FMU_quad_+

View File

@ -1,14 +1,13 @@
#!nsh
#
# USB HIL start
# HIL Rascal 110 (Flightgear)
#
# 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,59 +39,8 @@ 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
set HIL yes
# 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)
#
set MODE autostart
mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
if [ -f /fs/microsd/etc/mixers/FMU_AERT.mix ]
then
echo "Using /fs/microsd/etc/mixers/FMU_AERT.mix"
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_AERT.mix
else
echo "Using /etc/mixers/FMU_AERT.mix"
mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
fi
fw_pos_control_l1 start
fw_att_control start
echo "[HIL] setup done, running"
set VEHICLE_TYPE fw
set MIXER FMU_AERT

View File

@ -1,13 +1,15 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
#
# Load default params for this platform
# MPX EasyStar Plane
#
if param compare SYS_AUTOCONFIG 1
# Maintainers: ???
#
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
#
# Default parameters for this platform
#
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
@ -31,50 +33,7 @@ then
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
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
#
# Start and configure PX4IO or FMU interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
sh /etc/init.d/rc.io
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
px4io limit 100
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
fmu mode_pwm
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
fi
#
# Load mixer and start controllers (depends on px4io)
#
if [ -f /fs/microsd/etc/mixers/FMU_RET.mix ]
then
echo "Using /fs/microsd/etc/mixers/FMU_RET.mix"
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_RET.mix
else
echo "Using /etc/mixers/FMU_RET.mix"
mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
fi
#
# Start common fixedwing apps
#
sh /etc/init.d/rc.fixedwing
set VEHICLE_TYPE fw
set MIXER FMU_RET

View File

@ -1,85 +0,0 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on Phantom FPV"
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
param set FW_AIRSPD_MIN 11.4
param set FW_AIRSPD_TRIM 14
param set FW_AIRSPD_MAX 22
param set FW_L1_PERIOD 15
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
param set FW_P_LIM_MAX 45
param set FW_P_LIM_MIN -45
param set FW_P_P 60
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 2
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 15
param set FW_R_P 80
param set FW_R_RMAX 60
param set FW_THR_CRUISE 0.8
param set FW_THR_LND_MAX 0
param set FW_THR_MAX 1
param set FW_THR_MIN 0.5
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 2.0
param set FW_Y_ROLLFF 1.0
param set RC_SCALE_ROLL 0.6
param set RC_SCALE_PITCH 0.6
param set TRIM_PITCH 0.1
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 and configure PX4IO or FMU interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
sh /etc/init.d/rc.io
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
px4io limit 100
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
fmu mode_pwm
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
fi
#
# Load mixer and start controllers (depends on px4io)
#
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
then
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
else
echo "Using /etc/mixers/FMU_Q.mix"
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fi
#
# Start common fixedwing apps
#
sh /etc/init.d/rc.fixedwing

View File

@ -0,0 +1,44 @@
#!nsh
#
# Phantom FPV Flying Wing
#
# Maintainers: Simon Wilks <sjwilks@gmail.com>
#
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set FW_AIRSPD_MIN 11.4
param set FW_AIRSPD_TRIM 14
param set FW_AIRSPD_MAX 22
param set FW_L1_PERIOD 15
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
param set FW_P_LIM_MAX 45
param set FW_P_LIM_MIN -45
param set FW_P_P 60
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 2
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 15
param set FW_R_P 80
param set FW_R_RMAX 60
param set FW_THR_CRUISE 0.8
param set FW_THR_LND_MAX 0
param set FW_THR_MAX 1
param set FW_THR_MIN 0.5
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 2.0
param set FW_Y_ROLLFF 1.0
param set RC_SCALE_ROLL 0.6
param set RC_SCALE_PITCH 0.6
param set TRIM_PITCH 0.1
fi
set VEHICLE_TYPE fw
set MIXER FMU_Q

View File

@ -1,58 +1,14 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on Skywalker X5"
#
# Load default params for this platform
# Skywalker X5 Flying Wing
#
if param compare SYS_AUTOCONFIG 1
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>, Julian Oes <joes@student.ethz.ch>
#
if [ $DO_AUTOCONFIG == yes ]
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 and configure PX4IO or FMU interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
sh /etc/init.d/rc.io
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
px4io limit 100
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
fmu mode_pwm
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
fi
#
# Load mixer and start controllers (depends on px4io)
#
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
then
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
else
echo "Using /etc/mixers/FMU_Q.mix"
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fi
#
# Start common fixedwing apps
#
sh /etc/init.d/rc.fixedwing
set VEHICLE_TYPE fw
set MIXER FMU_Q

View File

@ -1,84 +0,0 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on the Wing Wing (aka Z-84)"
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
param set FW_AIRSPD_MIN 7
param set FW_AIRSPD_TRIM 9
param set FW_AIRSPD_MAX 14
param set FW_L1_PERIOD 10
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 20
param set FW_P_LIM_MAX 30
param set FW_P_LIM_MIN -20
param set FW_P_P 30
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 2
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 20
param set FW_R_P 60
param set FW_R_RMAX 60
param set FW_THR_CRUISE 0.65
param set FW_THR_MAX 0.7
param set FW_THR_MIN 0
param set FW_T_SINK_MAX 5
param set FW_T_SINK_MIN 2
param set FW_T_TIME_CONST 9
param set FW_Y_ROLLFF 2.0
param set RC_SCALE_ROLL 1.0
param set RC_SCALE_PITCH 1.0
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 and configure PX4IO or FMU interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
sh /etc/init.d/rc.io
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
px4io limit 100
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
fmu mode_pwm
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
fi
#
# Load mixer and start controllers (depends on px4io)
#
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
then
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
else
echo "Using /etc/mixers/FMU_Q.mix"
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fi
#
# Start common fixedwing apps
#
sh /etc/init.d/rc.fixedwing

View File

@ -0,0 +1,43 @@
#!nsh
#
# Wing Wing (aka Z-84) Flying Wing
#
# Maintainers: Simon Wilks <sjwilks@gmail.com>
#
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set FW_AIRSPD_MIN 7
param set FW_AIRSPD_TRIM 9
param set FW_AIRSPD_MAX 14
param set FW_L1_PERIOD 10
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 20
param set FW_P_LIM_MAX 30
param set FW_P_LIM_MIN -20
param set FW_P_P 30
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 2
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 20
param set FW_R_P 60
param set FW_R_RMAX 60
param set FW_THR_CRUISE 0.65
param set FW_THR_MAX 0.7
param set FW_THR_MIN 0
param set FW_T_SINK_MAX 5
param set FW_T_SINK_MIN 2
param set FW_T_TIME_CONST 9
param set FW_Y_ROLLFF 2.0
param set RC_SCALE_ROLL 1.0
param set RC_SCALE_PITCH 1.0
fi
set VEHICLE_TYPE fw
set MIXER FMU_Q

View File

@ -0,0 +1,43 @@
#!nsh
#
# FX-79 Buffalo Flying Wing
#
# Maintainers: Simon Wilks <sjwilks@gmail.com>
#
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set FW_AIRSPD_MAX 20
param set FW_AIRSPD_TRIM 12
param set FW_AIRSPD_MIN 15
param set FW_L1_PERIOD 12
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
param set FW_P_LIM_MAX 50
param set FW_P_LIM_MIN -50
param set FW_P_P 60
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 1.1
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 20
param set FW_R_P 80
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.75
param set FW_THR_MAX 1
param set FW_THR_MIN 0
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 4.0
param set FW_T_TIME_CONST 9
param set FW_Y_ROLLFF 1.1
param set RC_SCALE_ROLL 1.0
param set RC_SCALE_PITCH 1.0
fi
set VEHICLE_TYPE fw
set MIXER FMU_FX79

View File

@ -1,84 +0,0 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on FX-79 Buffalo"
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
param set FW_AIRSPD_MAX 20
param set FW_AIRSPD_TRIM 12
param set FW_AIRSPD_MIN 15
param set FW_L1_PERIOD 12
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
param set FW_P_LIM_MAX 50
param set FW_P_LIM_MIN -50
param set FW_P_P 60
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 1.1
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 20
param set FW_R_P 80
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.75
param set FW_THR_MAX 1
param set FW_THR_MIN 0
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 4.0
param set FW_T_TIME_CONST 9
param set FW_Y_ROLLFF 1.1
param set RC_SCALE_ROLL 1.0
param set RC_SCALE_PITCH 1.0
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 and configure PX4IO or FMU interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
sh /etc/init.d/rc.io
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
px4io limit 100
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
fmu mode_pwm
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
fi
#
# Load mixer and start controllers (depends on px4io)
#
if [ -f /fs/microsd/etc/mixers/FMU_FX79.mix ]
then
echo "Using /fs/microsd/etc/mixers/FMU_FX79.mix"
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_FX79.mix
else
echo "Using /etc/mixers/FMU_FX79.mix"
mixer load /dev/pwm_output /etc/mixers/FMU_FX79.mix
fi
#
# Start common fixedwing apps
#
sh /etc/init.d/rc.fixedwing

View File

@ -1,31 +1,31 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
#
# Load default params for this platform
# DJI Flame Wheel F330 Quadcopter
#
if param compare SYS_AUTOCONFIG 1
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
if [ $DO_AUTOCONFIG == yes ]
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
#
# Default parameters for this platform
#
param set MC_ATT_P 7.0
param set MC_YAWPOS_D 0.0
param set MC_ATT_I 0.0
param set MC_ATT_D 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_YAWPOS_P 2.8
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 set NAV_TAKEOFF_ALT 3.0
param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.05
param set MC_YAWRATE_D 0.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.7
param set MPC_THR_MIN 0.3
param set MPC_THR_MAX 0.8
param set MPC_THR_MIN 0.2
param set MPC_XY_D 0
param set MPC_XY_P 0.5
param set MPC_XY_VEL_D 0
@ -38,32 +38,14 @@ then
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
#
# Start and configure PX4IO or FMU interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
usleep 5000
set VEHICLE_TYPE mc
set MIXER FMU_quad_x
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
fi
sh /etc/init.d/rc.mc_interface
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
set PWM_OUTPUTS 1234
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
set PWM_MIN 1200
set PWM_MAX 1900

View File

@ -1,74 +1,37 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on DJI F450"
#
# Load default params for this platform
# DJI Flame Wheel F450 Quadcopter
#
if param compare SYS_AUTOCONFIG 1
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
#
if [ $DO_AUTOCONFIG == yes ]
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
#
# Default parameters for this platform
#
param set MC_ATT_P 7.0
param set MC_YAWPOS_D 0.0
param set MC_YAWPOS_I 0.0
param set MC_ATT_I 0.0
param set MC_ATT_D 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_YAWPOS_P 2.0
param set MC_YAWRATE_D 0.005
param set MC_YAWRATE_I 0.2
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_D 0.0
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
#
# 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
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
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.005
# TODO add default MPC parameters
fi
#
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
set VEHICLE_TYPE mc
set MIXER FMU_quad_x
#
# Set PWM output frequency
#
pwm rate -c 1234 -r 400
#
# Set disarmed, min and max PWM signals (for DJI ESCs)
#
pwm disarmed -c 1234 -p 900
pwm min -c 1234 -p 1200
pwm max -c 1234 -p 1800
#
# Start common multirotor apps
#
sh /etc/init.d/rc.multirotor
set PWM_OUTPUTS 1234
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
set PWM_MIN 1200
set PWM_MAX 1900

View File

@ -0,0 +1,33 @@
#!nsh
#
# HobbyKing X550 Quadcopter
#
# Maintainers: Todd Stellanova <tstellanova@gmail.com>
#
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
param set MC_ATT_P 5.5
param set MC_ATT_I 0
param set MC_ATT_D 0
param set MC_ATTRATE_P 0.14
param set MC_ATTRATE_I 0
param set MC_ATTRATE_D 0.006
param set MC_YAWPOS_P 0.6
param set MC_YAWPOS_I 0
param set MC_YAWPOS_D 0
param set MC_YAWRATE_P 0.08
param set MC_YAWRATE_I 0
param set MC_YAWRATE_D 0
# TODO add default MPC parameters
fi
set VEHICLE_TYPE mc
set MIXER FMU_quad_x
set PWM_OUTPUTS 1234
set PWM_RATE 400

View File

@ -1,51 +0,0 @@
#!nsh
#
# 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 10 = ground rover
#
param set MAV_TYPE 10
#
# 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
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude estimator (depends on orb)
#
attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
roboclaw start /dev/ttyS2 128 1200
segway start

View File

@ -1,76 +0,0 @@
#!nsh
echo "[init] 666_fmu_q_x550: PX4FMU Quad X550 with or without IO"
#
# 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 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
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
fi
#
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
pwm rate -c 1234 -r 400
#
# 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

View File

@ -1,51 +0,0 @@
#!nsh
echo "[init] PX4FMU v1, v2 init to log only
#
# 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 save
fi
#
# 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
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
usleep 5000
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
fi
sh /etc/init.d/rc.sensors
gps start
attitude_estimator_ekf start
position_estimator_inav start
if [ -d /fs/microsd ]
then
if [ $BOARD == fmuv1 ]
then
sdlog2 start -r 50 -e -b 16
else
sdlog2 start -r 200 -e -b 16
fi
fi

View File

@ -0,0 +1,141 @@
#
# Check if auto-setup from one of the standard scripts is wanted
# SYS_AUTOSTART = 0 means no autostart (default)
#
# AUTOSTART PARTITION:
# 0 .. 999 Reserved (historical)
# 1000 .. 1999 Simulation setups
# 2000 .. 2999 Standard planes
# 3000 .. 3999 Flying wing
# 4000 .. 4999 Quad X
# 5000 .. 5999 Quad +
# 6000 .. 6999 Hexa X
# 7000 .. 7999 Hexa +
# 8000 .. 8999 Octo X
# 9000 .. 9999 Octo +
# 10000 .. 10999 Wide arm / H frame
# 11000 .. 11999 Hexa Cox
# 12000 .. 12999 Octo Cox
#
# Simulation setups
#
if param compare SYS_AUTOSTART 1000
then
#sh /etc/init.d/1000_rc_fw_easystar.hil
fi
if param compare SYS_AUTOSTART 1001
then
sh /etc/init.d/1001_rc_quad_x.hil
fi
if param compare SYS_AUTOSTART 1002
then
#sh /etc/init.d/1002_rc_fw_state.hil
fi
if param compare SYS_AUTOSTART 1003
then
sh /etc/init.d/1003_rc_quad_+.hil
fi
if param compare SYS_AUTOSTART 1004
then
sh /etc/init.d/1004_rc_fw_Rascal110.hil
fi
#
# Standard plane
#
if param compare SYS_AUTOSTART 2100 100
then
#sh /etc/init.d/2100_mpx_easystar
#set MODE custom
fi
if param compare SYS_AUTOSTART 2101 101
then
#sh /etc/init.d/2101_hk_bixler
#set MODE custom
fi
if param compare SYS_AUTOSTART 2102 102
then
#sh /etc/init.d/2102_3dr_skywalker
#set MODE custom
fi
#
# Flying wing
#
if param compare SYS_AUTOSTART 3030
then
#sh /etc/init.d/3030_io_camflyer
fi
if param compare SYS_AUTOSTART 3031
then
sh /etc/init.d/3031_phantom
fi
if param compare SYS_AUTOSTART 3032
then
sh /etc/init.d/3032_skywalker_x5
fi
if param compare SYS_AUTOSTART 3033
then
sh /etc/init.d/3033_wingwing
fi
if param compare SYS_AUTOSTART 3034
then
sh /etc/init.d/3034_fx79
fi
#
# Quad X
#
if param compare SYS_AUTOSTART 4008
then
#sh /etc/init.d/4008_ardrone
fi
if param compare SYS_AUTOSTART 4009
then
#sh /etc/init.d/4009_ardrone_flow
fi
if param compare SYS_AUTOSTART 4010
then
sh /etc/init.d/4010_dji_f330
fi
if param compare SYS_AUTOSTART 4011
then
sh /etc/init.d/4011_dji_f450
fi
if param compare SYS_AUTOSTART 4012
then
sh /etc/init.d/4012_hk_x550
fi
#
# Wide arm / H frame
#
if param compare SYS_AUTOSTART 10015
then
sh /etc/init.d/10015_tbs_discovery
fi
if param compare SYS_AUTOSTART 10016
then
sh /etc/init.d/10016_3dr_iris
fi

View File

@ -1,113 +0,0 @@
#!nsh
#
# 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.002
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_P 0.09
param set MC_ATT_D 0.0
param set MC_ATT_I 0.0
param set MC_ATT_P 6.8
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 set NAV_TAKEOFF_ALT 3.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.7
param set MPC_THR_MIN 0.3
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
#
# Force some key parameters to sane values
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
set EXIT_ON_END no
#
# Start the Mikrokopter ESC driver
#
if [ $MKBLCTRL_MODE == yes ]
then
if [ $MKBLCTRL_FRAME == x ]
then
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing"
mkblctrl -mkmode x
else
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing"
mkblctrl -mkmode +
fi
else
if [ $MKBLCTRL_FRAME == x ]
then
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame"
else
echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame"
fi
mkblctrl
fi
usleep 10000
#
# 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
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
fi
#
# Load mixer
#
if [ $MKBLCTRL_FRAME == x ]
then
mixer load /dev/mkblctrl /etc/mixers/FMU_quad_x.mix
else
mixer load /dev/mkblctrl /etc/mixers/FMU_quad_+.mix
fi
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
if [ $EXIT_ON_END == yes ]
then
exit
fi

View File

@ -1,120 +0,0 @@
#!nsh
#
# 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.002
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_P 0.09
param set MC_ATT_D 0.0
param set MC_ATT_I 0.0
param set MC_ATT_P 6.8
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 set NAV_TAKEOFF_ALT 3.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.7
param set MPC_THR_MIN 0.3
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
echo "RC script for PX4FMU + PX4IO + PPM-ESCs running"
#
# Force some key parameters to sane values
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
set EXIT_ON_END no
usleep 10000
#
# Start and configure PX4IO or FMU interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
sh /etc/init.d/rc.io
else
fmu mode_pwm
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
fi
if [ $ESC_MAKER = afro ]
then
# Set PWM values for Afro ESCs
pwm disarmed -c 1234 -p 1050
pwm min -c 1234 -p 1080
pwm max -c 1234 -p 1860
else
# Set PWM values for typical ESCs
pwm disarmed -c 1234 -p 900
pwm min -c 1234 -p 980
pwm max -c 1234 -p 1800
fi
#
# Load mixer
#
if [ $FRAME_GEOMETRY == x ]
then
echo "Frame geometry X"
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
else
if [ $FRAME_GEOMETRY == w ]
then
echo "Frame geometry W"
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
else
echo "Frame geometry +"
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
fi
fi
#
# Set PWM output frequency
#
pwm rate -r 400 -c 1234
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
if [ $EXIT_ON_END == yes ]
then
exit
fi
echo "Script end"

View File

@ -1,34 +0,0 @@
#!nsh
#
# Standard everything needed for fixedwing except mixer, actuator output and mavlink
#
#
# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
#
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude and position estimator
#
att_pos_estimator_ekf start
#
# Start attitude controller
#
fw_att_control start
#
# Start the position controller
#
fw_pos_control_l1 start

View File

@ -0,0 +1,19 @@
#!nsh
#
# Standard apps for fixed wing
#
#
# Start the attitude and position estimator
#
att_pos_estimator_ekf start
#
# Start attitude controller
#
fw_att_control start
#
# Start the position controller
#
fw_pos_control_l1 start

View File

@ -1,94 +0,0 @@
#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on Hex"
#
# 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_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 set NAV_TAKEOFF_ALT 3.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.7
param set MPC_THR_MIN 0.3
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
#
# Force some key parameters to sane values
# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
# 13 = hexarotor
#
param set MAV_TYPE 13
set EXIT_ON_END no
#
# Start and configure PX4IO interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
usleep 5000
sh /etc/init.d/rc.io
else
# This is not possible on a hexa
tone_alarm error
fi
#
# Load mixer
#
mixer load /dev/pwm_output $MIXER
#
# Set PWM output frequency to 400 Hz
#
pwm rate -a -r 400
#
# Set disarmed, min and max PWM signals
#
pwm disarmed -c 123456 -p 900
pwm min -c 123456 -p 1100
pwm max -c 123456 -p 1900
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
if [ $EXIT_ON_END == yes ]
then
exit
fi

View File

@ -0,0 +1,72 @@
#!nsh
#
# Script to configure control interface
#
if [ $MIXER != none ]
then
#
# Load mixer
#
set MIXERSD /fs/microsd/etc/mixers/$MIXER.mix
#Use the mixer file from the SD-card if it exists
if [ -f $MIXERSD ]
then
set MIXER_FILE $MIXERSD
else
set MIXER_FILE /etc/mixers/$MIXER.mix
fi
if [ $OUTPUT_MODE == mkblctrl ]
then
set OUTPUT_DEV /dev/mkblctrl
else
set OUTPUT_DEV /dev/pwm_output
fi
if mixer load $OUTPUT_DEV $MIXER_FILE
then
echo "[init] Mixer loaded: $MIXER_FILE"
else
echo "[init] Error loading mixer: $MIXER_FILE"
tone_alarm $TUNE_OUT_ERROR
fi
else
echo "[init] Mixer not defined"
tone_alarm $TUNE_OUT_ERROR
fi
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
then
if [ $PWM_OUTPUTS != none ]
then
#
# Set PWM output frequency
#
if [ $PWM_RATE != none ]
then
echo "[init] Set PWM rate: $PWM_RATE"
pwm rate -c $PWM_OUTPUTS -r $PWM_RATE
fi
#
# Set disarmed, min and max PWM values
#
if [ $PWM_DISARMED != none ]
then
echo "[init] Set PWM disarmed: $PWM_DISARMED"
pwm disarmed -c $PWM_OUTPUTS -p $PWM_DISARMED
fi
if [ $PWM_MIN != none ]
then
echo "[init] Set PWM min: $PWM_MIN"
pwm min -c $PWM_OUTPUTS -p $PWM_MIN
fi
if [ $PWM_MAX != none ]
then
echo "[init] Set PWM max: $PWM_MAX"
pwm max -c $PWM_OUTPUTS -p $PWM_MAX
fi
fi
fi

View File

@ -1,23 +1,21 @@
#
# Start PX4IO interface (depends on orb, commander)
# Init PX4IO interface
#
if px4io start
then
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
px4io recovery
#
# Disable px4io topic limiting
#
if [ $BOARD == fmuv1 ]
then
px4io limit 200
else
px4io limit 400
fi
else
# SOS
tone_alarm error
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
#
px4io recovery
#
# Adjust PX4IO update rate limit
#
set PX4IO_LIMIT 400
if hw_ver compare PX4FMU_V1
then
set PX4IO_LIMIT 200
fi
echo "[init] Set PX4IO update rate limit: $PX4IO_LIMIT Hz"
px4io limit $PX4IO_LIMIT

View File

@ -1,14 +1,14 @@
#!nsh
#
# Initialise logging services.
# Initialize logging services.
#
if [ -d /fs/microsd ]
then
if [ $BOARD == fmuv1 ]
if hw_ver compare PX4FMU_V1
then
sdlog2 start -r 50 -a -b 16
sdlog2 start -r 50 -a -b 16 -t
else
sdlog2 start -r 200 -a -b 16
sdlog2 start -r 200 -a -b 16 -t
fi
fi

View File

@ -0,0 +1,24 @@
#!nsh
#
# Standard apps for multirotors
#
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Start position estimator
#
position_estimator_inav start
#
# Start attitude control
#
multirotor_att_control start
#
# Start position control
#
multirotor_pos_control start

View File

@ -1,49 +0,0 @@
#!nsh
#
# Script to set PWM min / max limits and mixer
#
#
# Load mixer
#
if [ $FRAME_GEOMETRY == x ]
then
echo "Frame geometry X"
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
else
if [ $FRAME_GEOMETRY == w ]
then
echo "Frame geometry W"
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
else
echo "Frame geometry +"
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
fi
fi
if [ $FRAME_COUNT == 4 ]
then
set OUTPUTS 1234
param set MAV_TYPE 2
else
if [ $FRAME_COUNT == 6 ]
then
set OUTPUTS 123456
param set MAV_TYPE 13
else
set OUTPUTS 12345678
fi
fi
#
# Set PWM output frequency
#
pwm rate -c $OUTPUTS -r $PWM_RATE
#
# Set disarmed, min and max PWM signals (for DJI ESCs)
#
pwm disarmed -c $OUTPUTS -p $PWM_DISARMED
pwm min -c $OUTPUTS -p $PWM_MIN
pwm max -c $OUTPUTS -p $PWM_MAX

View File

@ -1,39 +0,0 @@
#!nsh
#
# Standard everything needed for multirotors except mixer, actuator output and mavlink
#
#
# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
#
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Start position estimator
#
position_estimator_inav start
#
# Start attitude control
#
multirotor_att_control start
#
# Start position control
#
multirotor_pos_control start

View File

@ -1,94 +0,0 @@
#!nsh
echo "[init] Octorotor startup"
#
# 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_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 set NAV_TAKEOFF_ALT 3.0
param set MPC_TILT_MAX 0.5
param set MPC_THR_MAX 0.7
param set MPC_THR_MIN 0.3
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
#
# Force some key parameters to sane values
# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
# 14 = octorotor
#
param set MAV_TYPE 14
set EXIT_ON_END no
#
# Start and configure PX4IO interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
usleep 5000
sh /etc/init.d/rc.io
else
# This is not possible on an octo
tone_alarm error
fi
#
# Load mixer
#
mixer load /dev/pwm_output $MIXER
#
# Set PWM output frequency to 400 Hz
#
pwm rate -a -r 400
#
# Set disarmed, min and max PWM signals
#
pwm disarmed -c 12345678 -p 900
pwm min -c 12345678 -p 1100
pwm max -c 12345678 -p 1900
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
if [ $EXIT_ON_END == yes ]
then
exit
fi

View File

@ -10,41 +10,42 @@
ms5611 start
adc start
# mag might be external
# Mag might be external
if hmc5883 start
then
echo "using HMC5883"
echo "[init] Using HMC5883"
fi
if mpu6000 start
then
echo "using MPU6000"
echo "[init] Using MPU6000"
fi
if l3gd20 start
then
echo "using L3GD20(H)"
echo "[init] Using L3GD20(H)"
fi
if lsm303d start
if hw_ver compare PX4FMU_V2
then
set BOARD fmuv2
else
set BOARD fmuv1
if lsm303d start
then
echo "[init] Using LSM303D"
fi
fi
# Start airspeed sensors
if meas_airspeed start
then
echo "using MEAS airspeed sensor"
echo "[init] Using MEAS airspeed sensor"
else
if ets_airspeed start
then
echo "using ETS airspeed sensor (bus 3)"
echo "[init] Using ETS airspeed sensor (bus 3)"
else
if ets_airspeed start -b 1
then
echo "Using ETS airspeed sensor (bus 1)"
echo "[init] Using ETS airspeed sensor (bus 1)"
fi
fi
fi

View File

@ -1,13 +0,0 @@
#!nsh
#
# Flight startup script for PX4FMU standalone configuration.
#
echo "[init] doing standalone PX4FMU startup..."
#
# Start the ORB
#
uorb start
echo "[init] startup done"

View File

@ -36,39 +36,6 @@ then
echo "Commander started"
fi
# Start px4io if present
if px4io start
then
echo "PX4IO driver started"
else
if fmu mode_serial
then
echo "FMU driver started"
fi
fi
# Start sensors
sh /etc/init.d/rc.sensors
# Start one of the estimators
if attitude_estimator_ekf status
then
echo "multicopter att filter running"
else
if att_pos_estimator_ekf status
then
echo "fixedwing att filter running"
else
attitude_estimator_ekf start
fi
fi
# Start GPS
if gps start
then
echo "GPS started"
fi
echo "MAVLink started, exiting shell.."
# Exit shell to make it available to MAVLink

View File

@ -8,39 +8,39 @@
#
set MODE autostart
set logfile /fs/microsd/bootlog.txt
set LOG_FILE /fs/microsd/bootlog.txt
set RC_FILE /fs/microsd/etc/rc.txt
set CONFIG_FILE /fs/microsd/etc/config.txt
set EXTRAS_FILE /fs/microsd/etc/extras.txt
set TUNE_OUT_ERROR ML<<CP4CP4CP4CP4CP4
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
echo "[init] Looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
echo "[init] microSD card mounted at /fs/microsd"
# Start playing the startup tune
tone_alarm start
else
echo "[init] no microSD card found"
echo "[init] No microSD card found"
# Play SOS
tone_alarm error
fi
#
# Look for an init script on the microSD card.
# Disable autostart if the script found.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
if [ -f $RC_FILE ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
echo "[init] Executing init script: $RC_FILE"
sh $RC_FILE
set MODE custom
else
echo "[init] Init script not found: $RC_FILE"
fi
# if this is an APM build then there will be a rc.APM script
@ -52,20 +52,19 @@ then
echo "[init] USB interface connected"
fi
echo "Running rc.APM"
echo "[init] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
fi
if [ $MODE == autostart ]
then
echo "[init] AUTOSTART mode"
#
# Start terminal
# Start CDC/ACM serial driver
#
if sercon
then
echo "USB connected"
fi
sercon
#
# Start the ORB (first app to start)
@ -73,27 +72,20 @@ then
uorb start
#
# Load microSD params
# Load parameters
#
set PARAM_FILE /fs/microsd/params
if mtd start
then
param select /fs/mtd_params
if param load /fs/mtd_params
then
else
echo "FAILED LOADING PARAMS"
fi
set PARAM_FILE /fs/mtd_params
fi
param select $PARAM_FILE
if param load
then
echo "[init] Parameters loaded: $PARAM_FILE"
else
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
if param load /fs/microsd/params
then
echo "Parameters loaded"
else
echo "Parameter file corrupt - ignoring"
fi
fi
echo "[init] ERROR: Parameters loading failed: $PARAM_FILE"
fi
#
@ -101,355 +93,416 @@ then
#
if rgbled start
then
echo "Using external RGB Led"
echo "[init] Using external RGB Led"
else
if blinkm start
then
echo "[init] Using blinkm"
blinkm systemstate
fi
fi
#
# Set default values
#
set HIL no
set VEHICLE_TYPE none
set MIXER none
set USE_IO yes
set OUTPUT_MODE none
set PWM_OUTPUTS none
set PWM_RATE none
set PWM_DISARMED none
set PWM_MIN none
set PWM_MAX none
set MKBLCTRL_MODE none
set FMU_MODE pwm
set MAV_TYPE none
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
#
if param compare SYS_AUTOCONFIG 1
then
set DO_AUTOCONFIG yes
else
set DO_AUTOCONFIG no
fi
#
# Set parameters and env variables for selected AUTOSTART
#
if param compare SYS_AUTOSTART 0
then
echo "[init] Don't try to find autostart script"
else
sh /etc/init.d/rc.autostart
fi
#
# Override parameters from user configuration file
#
if [ -f $CONFIG_FILE ]
then
echo "[init] Reading config: $CONFIG_FILE"
sh $CONFIG_FILE
else
echo "[init] Config file not found: $CONFIG_FILE"
fi
#
# If autoconfig parameter was set, reset it and save parameters
#
if [ $DO_AUTOCONFIG == yes ]
then
param set SYS_AUTOCONFIG 0
param save
fi
set IO_PRESENT no
if [ $USE_IO == yes ]
then
#
# Check if PX4IO present and update firmware if needed
#
if [ -f /etc/extras/px4io-v2_default.bin ]
then
set IO_FILE /etc/extras/px4io-v2_default.bin
else
set IO_FILE /etc/extras/px4io-v1_default.bin
fi
if px4io checkcrc $IO_FILE
then
echo "[init] PX4IO CRC OK"
echo "PX4IO CRC OK" >> $LOG_FILE
set IO_PRESENT yes
else
echo "[init] PX4IO CRC failure, trying to update"
echo "PX4IO CRC failure" >> $LOG_FILE
tone_alarm MLL32CP8MB
if px4io forceupdate 14662 $IO_FILE
then
usleep 500000
if px4io checkcrc $IO_FILE
then
echo "[init] PX4IO CRC OK, update successful"
echo "PX4IO CRC OK after updating" >> $LOG_FILE
tone_alarm MLL8CDE
set IO_PRESENT yes
else
echo "[init] ERROR: PX4IO update failed"
echo "PX4IO update failed" >> $LOG_FILE
fi
else
echo "[init] ERROR: PX4IO update failed"
echo "PX4IO update failed" >> $LOG_FILE
fi
fi
if [ $IO_PRESENT == no ]
then
echo "[init] ERROR: PX4IO not found"
tone_alarm $TUNE_OUT_ERROR
fi
fi
#
# 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
if [ $OUTPUT_MODE == io -a $IO_PRESENT != yes ]
then
# Need IO for output but it not present, disable output
set OUTPUT_MODE none
echo "[init] ERROR: PX4IO not found, disabling output"
# Avoid using ttyS0 for MAVLink on FMUv1
if hw_ver compare PX4FMU_V1
then
set FMU_MODE serial
fi
fi
if [ $HIL == yes ]
then
set OUTPUT_MODE hil
if hw_ver compare PX4FMU_V1
then
set FMU_MODE serial
fi
else
# Try to get an USB console if not in HIL mode
nshterm /dev/ttyACM0 &
fi
#
# Start the Commander (needs to be this early for in-air-restarts)
#
commander start
if param compare SYS_AUTOSTART 1000
then
sh /etc/init.d/1000_rc_fw_easystar.hil
set MODE custom
fi
if param compare SYS_AUTOSTART 1001
then
sh /etc/init.d/1001_rc_quad.hil
set MODE custom
fi
if param compare SYS_AUTOSTART 1002
then
sh /etc/init.d/1002_rc_fw_state.hil
set MODE custom
fi
if param compare SYS_AUTOSTART 1003
then
sh /etc/init.d/1003_rc_quad_+.hil
set MODE custom
fi
if param compare SYS_AUTOSTART 1004
then
sh /etc/init.d/1004_rc_fw_Rascal110.hil
set MODE custom
fi
if [ $MODE != custom ]
then
# Try to get an USB console
nshterm /dev/ttyACM0 &
fi
#
# Upgrade PX4IO firmware
# Start primary output
#
if [ -f /etc/extras/px4io-v2_default.bin ]
then
set io_file /etc/extras/px4io-v2_default.bin
else
set io_file /etc/extras/px4io-v1_default.bin
fi
if px4io start
then
echo "PX4IO OK"
echo "PX4IO OK" >> $logfile
fi
set TTYS1_BUSY no
if px4io checkcrc $io_file
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
if [ $OUTPUT_MODE != none ]
then
echo "PX4IO CRC OK"
echo "PX4IO CRC OK" >> $logfile
else
echo "PX4IO CRC failure"
echo "PX4IO CRC failure" >> $logfile
tone_alarm MBABGP
if px4io forceupdate 14662 $io_file
if [ $OUTPUT_MODE == io ]
then
usleep 500000
echo "[init] Use PX4IO PWM as primary output"
if px4io start
then
echo "PX4IO restart OK"
echo "PX4IO restart OK" >> $logfile
tone_alarm MSPAA
echo "[init] PX4IO started"
sh /etc/init.d/rc.io
else
echo "PX4IO restart failed"
echo "PX4IO restart failed" >> $logfile
tone_alarm MNGGG
sleep 10
reboot
echo "[init] ERROR: PX4IO start failed"
tone_alarm $TUNE_OUT_ERROR
fi
fi
if [ $OUTPUT_MODE == fmu ]
then
echo "[init] Use FMU PWM as primary output"
if fmu mode_$FMU_MODE
then
echo "[init] FMU mode_$FMU_MODE started"
else
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
tone_alarm $TUNE_OUT_ERROR
fi
if hw_ver compare PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
then
set TTYS1_BUSY yes
fi
if [ $FMU_MODE == pwm_gpio ]
then
set TTYS1_BUSY yes
fi
fi
fi
if [ $OUTPUT_MODE == mkblctrl ]
then
echo "[init] Use MKBLCTRL as primary output"
set MKBLCTRL_ARG ""
if [ $MKBLCTRL_MODE == x ]
then
set MKBLCTRL_ARG "-mkmode x"
fi
if [ $MKBLCTRL_MODE == + ]
then
set MKBLCTRL_ARG "-mkmode +"
fi
if mkblctrl $MKBLCTRL_ARG
then
echo "[init] MKBLCTRL started"
else
echo "[init] ERROR: MKBLCTRL start failed"
tone_alarm $TUNE_OUT_ERROR
fi
fi
if [ $OUTPUT_MODE == hil ]
then
echo "[init] Use HIL as primary output"
if hil mode_pwm
then
echo "[init] HIL output started"
else
echo "[init] ERROR: HIL output start failed"
tone_alarm $TUNE_OUT_ERROR
fi
fi
#
# Start IO or FMU for RC PPM input if needed
#
if [ $IO_PRESENT == yes ]
then
if [ $OUTPUT_MODE != io ]
then
if px4io start
then
echo "[init] PX4IO started"
sh /etc/init.d/rc.io
else
echo "[init] ERROR: PX4IO start failed"
tone_alarm $TUNE_OUT_ERROR
fi
fi
else
echo "PX4IO update failed"
echo "PX4IO update failed" >> $logfile
tone_alarm MNGGG
if [ $OUTPUT_MODE != fmu ]
then
if fmu mode_$FMU_MODE
then
echo "[init] FMU mode_$FMU_MODE started"
else
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
tone_alarm $TUNE_OUT_ERROR
fi
if hw_ver compare PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
then
set TTYS1_BUSY yes
fi
if [ $FMU_MODE == pwm_gpio ]
then
set TTYS1_BUSY yes
fi
fi
fi
fi
fi
#
# MAVLink
#
set EXIT_ON_END no
#
# Check if auto-setup from one of the standard scripts is wanted
# SYS_AUTOSTART = 0 means no autostart (default)
#
# AUTOSTART PARTITION:
# 0 .. 999 Reserved (historical)
# 1000 .. 1999 Simulation setups
# 2000 .. 2999 Standard planes
# 3000 .. 3999 Flying wing
# 4000 .. 4999 Quad X
# 5000 .. 5999 Quad +
# 6000 .. 6999 Hexa X
# 7000 .. 7999 Hexa +
# 8000 .. 8999 Octo X
# 9000 .. 9999 Octo +
# 10000 .. 10999 Wide arm / H frame
# 11000 .. 11999 Hexa Cox
# 12000 .. 12999 Octo Cox
if param compare SYS_AUTOSTART 4008 8
if [ $HIL == yes ]
then
sh /etc/init.d/4008_ardrone
set MODE custom
fi
if param compare SYS_AUTOSTART 4009 9
then
sh /etc/init.d/4009_ardrone_flow
set MODE custom
fi
if param compare SYS_AUTOSTART 4010 10
then
set FRAME_GEOMETRY x
set FRAME_COUNT 4
set PWM_MIN 1200
set PWM_MAX 1900
set PWM_DISARMED 900
sh /etc/init.d/4010_dji_f330
set MODE custom
fi
if param compare SYS_AUTOSTART 4011 11
then
sh /etc/init.d/4011_dji_f450
set MODE custom
fi
if param compare SYS_AUTOSTART 4012
then
sh /etc/init.d/666_fmu_q_x550
set MODE custom
fi
if param compare SYS_AUTOSTART 6012 12
then
set MIXER /etc/mixers/FMU_hex_x.mix
sh /etc/init.d/rc.hexa
set MODE custom
fi
if param compare SYS_AUTOSTART 7013 13
then
set MIXER /etc/mixers/FMU_hex_+.mix
sh /etc/init.d/rc.hexa
set MODE custom
fi
if param compare SYS_AUTOSTART 8001
then
set MIXER /etc/mixers/FMU_octo_x.mix
sh /etc/init.d/rc.octo
set MODE custom
fi
if param compare SYS_AUTOSTART 9001
then
set MIXER /etc/mixers/FMU_octo_+.mix
sh /etc/init.d/rc.octo
set MODE custom
fi
if param compare SYS_AUTOSTART 12001
then
set MIXER /etc/mixers/FMU_octo_cox.mix
sh /etc/init.d/rc.octo
set MODE custom
fi
if param compare SYS_AUTOSTART 10015 15
then
sh /etc/init.d/10015_tbs_discovery
set MODE custom
fi
if param compare SYS_AUTOSTART 10016 16
then
sh /etc/init.d/10016_3dr_iris
set MODE custom
fi
# PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame
if param compare SYS_AUTOSTART 4017 17
then
set MKBLCTRL_MODE no
set MKBLCTRL_FRAME x
sh /etc/init.d/rc.custom_dji_f330_mkblctrl
set MODE custom
fi
# PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame
if param compare SYS_AUTOSTART 5018 18
then
set MKBLCTRL_MODE no
set MKBLCTRL_FRAME +
sh /etc/init.d/rc.custom_dji_f330_mkblctrl
set MODE custom
fi
# PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing
if param compare SYS_AUTOSTART 4019 19
then
set MKBLCTRL_MODE yes
set MKBLCTRL_FRAME x
sh /etc/init.d/rc.custom_dji_f330_mkblctrl
set MODE custom
fi
# PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing
if param compare SYS_AUTOSTART 5020 20
then
set MKBLCTRL_MODE yes
set MKBLCTRL_FRAME +
sh /etc/init.d/rc.custom_dji_f330_mkblctrl
set MODE custom
fi
# PX4FMU v1 with IO + PPM-based ESCs on Quad X-shape frame
if param compare SYS_AUTOSTART 4021 21
then
set FRAME_GEOMETRY x
set ESC_MAKER afro
sh /etc/init.d/rc.custom_io_esc
set MODE custom
fi
# PX4FMU v1 with IO + PPM-based ESCs on Quad X-shape frame
if param compare SYS_AUTOSTART 10022 22
then
set FRAME_GEOMETRY w
sh /etc/init.d/rc.custom_io_esc
set MODE custom
fi
if param compare SYS_AUTOSTART 3030 30
then
sh /etc/init.d/3030_io_camflyer
set MODE custom
fi
if param compare SYS_AUTOSTART 3031 31
then
sh /etc/init.d/3031_io_phantom
set MODE custom
fi
if param compare SYS_AUTOSTART 3032 32
then
sh /etc/init.d/3032_skywalker_x5
set MODE custom
fi
if param compare SYS_AUTOSTART 3033 33
then
sh /etc/init.d/3033_io_wingwing
set MODE custom
fi
if param compare SYS_AUTOSTART 3034 34
then
sh /etc/init.d/3034_io_fx79
set MODE custom
fi
if param compare SYS_AUTOSTART 40
then
sh /etc/init.d/40_io_segway
set MODE custom
fi
if param compare SYS_AUTOSTART 2100 100
then
sh /etc/init.d/2100_mpx_easystar
set MODE custom
fi
if param compare SYS_AUTOSTART 2101 101
then
sh /etc/init.d/2101_hk_bixler
set MODE custom
fi
if param compare SYS_AUTOSTART 2102 102
then
sh /etc/init.d/2102_3dr_skywalker
set MODE custom
fi
if param compare SYS_AUTOSTART 800
then
sh /etc/init.d/800_sdlogger
set MODE custom
fi
# Start any custom extensions that might be missing
if [ -f /fs/microsd/etc/rc.local ]
then
sh /fs/microsd/etc/rc.local
fi
# If none of the autostart scripts triggered, get a minimal setup
if [ $MODE == autostart ]
then
# Telemetry port is on both FMU boards ttyS1
# but the AR.Drone motors can be get 'flashed'
# if starting MAVLink on them - so do not
# start it as default (default link: USB)
# Start commander
commander start
# Start px4io if present
if px4io detect
sleep 1
mavlink start -b 230400 -d /dev/ttyACM0
usleep 5000
else
if [ $TTYS1_BUSY == yes ]
then
px4io start
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
mavlink start -d /dev/ttyS0
usleep 5000
# Exit from nsh to free port for mavlink
set EXIT_ON_END yes
else
if fmu mode_serial
# Start MAVLink on default port: ttyS1
mavlink start
usleep 5000
fi
fi
#
# Sensors, Logging, GPS
#
echo "[init] Start sensors"
sh /etc/init.d/rc.sensors
if [ $HIL == no ]
then
echo "[init] Start logging"
sh /etc/init.d/rc.logging
echo "[init] Start GPS"
gps start
fi
#
# Fixed wing setup
#
if [ $VEHICLE_TYPE == fw ]
then
echo "[init] Vehicle type: FIXED WING"
if [ $MIXER == none ]
then
# Set default mixer for fixed wing if not defined
set MIXER FMU_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 "[init] Vehicle type: MULTICOPTER"
if [ $MIXER == none ]
then
# Set default mixer for multicopter if not defined
set MIXER quad_x
fi
if [ $MAV_TYPE == none ]
then
# Use MAV_TYPE = 2 (quadcopter) if not defined
set MAV_TYPE 2
# Use mixer to detect vehicle type
if [ $MIXER == FMU_hex_x -o $MIXER == FMU_hex_+ ]
then
echo "FMU driver (no PWM) started"
param set MAV_TYPE 13
fi
if [ $MIXER == FMU_octo_x -o $MIXER == FMU_octo_+ ]
then
param set MAV_TYPE 14
fi
if [ $MIXER == FMU_octo_cox ]
then
param set MAV_TYPE 14
fi
fi
# Start sensors
sh /etc/init.d/rc.sensors
# Start one of the estimators
attitude_estimator_ekf start
# Start GPS
gps start
param set MAV_TYPE $MAV_TYPE
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
# Start standard multicopter apps
sh /etc/init.d/rc.mc_apps
fi
#
# Generic setup (autostart ID not found)
#
if [ $VEHICLE_TYPE == none ]
then
echo "[init] Vehicle type: GENERIC"
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
fi
# Start any custom addons
if [ -f $EXTRAS_FILE ]
then
echo "[init] Starting addons script: $EXTRAS_FILE"
sh $EXTRAS_FILE
else
echo "[init] Addons script not found: $EXTRAS_FILE"
fi
if [ $EXIT_ON_END == yes ]

View File

@ -57,6 +57,7 @@ MODULES += systemcmds/top
MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
MODULES += systemcmds/hw_ver
#
# General system control

View File

@ -60,6 +60,7 @@ MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
MODULES += systemcmds/mtd
MODULES += systemcmds/hw_ver
#
# General system control

View File

@ -23,6 +23,7 @@ MODULES += systemcmds/reboot
MODULES += systemcmds/tests
MODULES += systemcmds/nshterm
MODULES += systemcmds/mtd
MODULES += systemcmds/hw_ver
#
# Library modules

View File

@ -1302,6 +1302,7 @@ PX4IO::io_handle_battery(uint16_t vbatt, uint16_t ibatt)
/* voltage is scaled to mV */
battery_status.voltage_v = vbatt / 1000.0f;
battery_status.voltage_filtered_v = vbatt / 1000.0f;
/*
ibatt contains the raw ADC count, as 12 bit ADC

View File

@ -33,15 +33,15 @@
****************************************************************************/
/**
* @file sdlog2_version.h
* @file version.h
*
* Tools for system version detection.
*
* @author Anton Babushkin <anton.babushkin@me.com>
*/
#ifndef SDLOG2_VERSION_H_
#define SDLOG2_VERSION_H_
#ifndef VERSION_H_
#define VERSION_H_
/*
GIT_VERSION is defined at build time via a Makefile call to the
@ -59,4 +59,4 @@
#define HW_ARCH "PX4FMU_V2"
#endif
#endif /* SDLOG2_VERSION_H_ */
#endif /* VERSION_H_ */

9
src/mainpage.dox Normal file
View File

@ -0,0 +1,9 @@
/**
\mainpage PX4 Autopilot Flight Control Stack and Middleware
This software repository offers a middleware for micro aerial vehicles capable of running efficiently on a 168 MHz Cortex M4F processor and a state of the art flight control stack supporting multicopter and fixed wing aircraft. It can be easily used for experimental air (and ground) vehicles as well, as the application on a spherical blimp shows.
http://pixhawk.org
*/

View File

@ -85,13 +85,13 @@
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <version/version.h>
#include <mavlink/mavlink_log.h>
#include "logbuffer.h"
#include "sdlog2_format.h"
#include "sdlog2_messages.h"
#include "sdlog2_version.h"
#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \
log_msgs_written++; \
@ -108,13 +108,13 @@ static bool main_thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */
static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log dirs */
static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
static const int LOG_BUFFER_SIZE_DEFAULT = 8192;
static const int MAX_WRITE_CHUNK = 512;
static const int MIN_BYTES_TO_WRITE = 512;
static const char *mountpoint = "/fs/microsd";
static const char *log_root = "/fs/microsd/log";
static int mavlink_fd = -1;
struct logbuffer_s lb;
@ -122,14 +122,17 @@ struct logbuffer_s lb;
static pthread_mutex_t logbuffer_mutex;
static pthread_cond_t logbuffer_cond;
static char folder_path[64];
static char log_dir[32];
/* statistics counters */
static unsigned long log_bytes_written = 0;
static uint64_t start_time = 0;
static unsigned long log_bytes_written = 0;
static unsigned long log_msgs_written = 0;
static unsigned long log_msgs_skipped = 0;
/* GPS time, used for log files naming */
static uint64_t gps_time = 0;
/* current state of logging */
static bool logging_enabled = false;
/* enable logging on start (-e option) */
@ -138,11 +141,14 @@ static bool log_on_start = false;
static bool log_when_armed = false;
/* delay = 1 / rate (rate defined by -r option) */
static useconds_t sleep_delay = 0;
/* use date/time for naming directories and files (-t option) */
static bool log_name_timestamp = false;
/* helper flag to track system state changes */
static bool flag_system_armed = false;
static pthread_t logwriter_pthread = 0;
static pthread_attr_t logwriter_attr;
/**
* Log buffer writing thread. Open and close file here.
@ -203,14 +209,14 @@ static void handle_command(struct vehicle_command_s *cmd);
static void handle_status(struct vehicle_status_s *cmd);
/**
* Create folder for current logging session. Store folder name in 'log_folder'.
* Create dir for current logging session. Store dir name in 'log_dir'.
*/
static int create_logfolder(void);
static int create_log_dir(void);
/**
* Select first free log file name and open it.
*/
static int open_logfile(void);
static int open_log_file(void);
static void
sdlog2_usage(const char *reason)
@ -218,11 +224,12 @@ sdlog2_usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a\n"
errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t\n"
"\t-r\tLog rate in Hz, 0 means unlimited rate\n"
"\t-b\tLog buffer size in KiB, default is 8\n"
"\t-e\tEnable logging by default (if not, can be started by command)\n"
"\t-a\tLog only when armed (can be still overriden by command)\n");
"\t-a\tLog only when armed (can be still overriden by command)\n"
"\t-t\tUse date/time for naming log directories and files\n");
}
/**
@ -280,82 +287,112 @@ int sdlog2_main(int argc, char *argv[])
exit(1);
}
int create_logfolder()
int create_log_dir()
{
/* make folder on sdcard */
uint16_t folder_number = 1; // start with folder sess001
/* create dir on sdcard if needed */
uint16_t dir_number = 1; // start with dir sess001
int mkdir_ret;
/* look for the next folder that does not exist */
while (folder_number <= MAX_NO_LOGFOLDER) {
/* set up folder path: e.g. /fs/microsd/sess001 */
sprintf(folder_path, "%s/sess%03u", mountpoint, folder_number);
mkdir_ret = mkdir(folder_path, S_IRWXU | S_IRWXG | S_IRWXO);
/* the result is -1 if the folder exists */
if (log_name_timestamp && gps_time != 0) {
/* use GPS date for log dir naming: e.g. /fs/microsd/2014-01-19 */
time_t gps_time_sec = gps_time / 1000000;
struct tm t;
gmtime_r(&gps_time_sec, &t);
int n = snprintf(log_dir, sizeof(log_dir), "%s/", log_root);
strftime(log_dir + n, sizeof(log_dir) - n, "%Y-%m-%d", &t);
mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
if (mkdir_ret == 0) {
/* folder does not exist, success */
break;
if (mkdir_ret == OK) {
warnx("log dir created: %s", log_dir);
} else if (mkdir_ret == -1) {
/* folder exists already */
folder_number++;
} else if (errno != EEXIST) {
warn("failed creating new dir: %s", log_dir);
return -1;
}
} else {
/* look for the next dir that does not exist */
while (dir_number <= MAX_NO_LOGFOLDER) {
/* format log dir: e.g. /fs/microsd/sess001 */
sprintf(log_dir, "%s/sess%03u", log_root, dir_number);
mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
if (mkdir_ret == 0) {
warnx("log dir created: %s", log_dir);
break;
} else if (errno != EEXIST) {
warn("failed creating new dir: %s", log_dir);
return -1;
}
/* dir exists already */
dir_number++;
continue;
}
} else {
warn("failed creating new folder");
if (dir_number >= MAX_NO_LOGFOLDER) {
/* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */
warnx("all %d possible dirs exist already", MAX_NO_LOGFOLDER);
return -1;
}
}
if (folder_number >= MAX_NO_LOGFOLDER) {
/* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */
warnx("all %d possible folders exist already.", MAX_NO_LOGFOLDER);
return -1;
}
/* print logging path, important to find log file later */
warnx("log dir: %s", log_dir);
mavlink_log_info(mavlink_fd, "[sdlog2] log dir: %s", log_dir);
return 0;
}
int open_logfile()
int open_log_file()
{
/* make folder on sdcard */
uint16_t file_number = 1; // start with file log001
/* string to hold the path to the log */
char path_buf[64] = "";
char log_file_name[16] = "";
char log_file_path[48] = "";
int fd = 0;
if (log_name_timestamp && gps_time != 0) {
/* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
time_t gps_time_sec = gps_time / 1000000;
struct tm t;
gmtime_r(&gps_time_sec, &t);
strftime(log_file_name, sizeof(log_file_name), "%H_%M_%S.bin", &t);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
/* look for the next file that does not exist */
while (file_number <= MAX_NO_LOGFILE) {
/* set up file path: e.g. /fs/microsd/sess001/log001.bin */
sprintf(path_buf, "%s/log%03u.bin", folder_path, file_number);
} else {
uint16_t file_number = 1; // start with file log001
/* look for the next file that does not exist */
while (file_number <= MAX_NO_LOGFILE) {
/* format log file path: e.g. /fs/microsd/sess001/log001.bin */
snprintf(log_file_name, sizeof(log_file_name), "log%03u.bin", file_number);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
if (!file_exist(log_file_path)) {
break;
}
if (file_exist(path_buf)) {
file_number++;
continue;
}
fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC);
if (fd == 0) {
warn("opening %s failed", path_buf);
if (file_number > MAX_NO_LOGFILE) {
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
warnx("all %d possible files exist already", MAX_NO_LOGFILE);
return -1;
}
warnx("logging to: %s.", path_buf);
mavlink_log_info(mavlink_fd, "[sdlog2] log: %s", path_buf);
return fd;
}
if (file_number > MAX_NO_LOGFILE) {
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
warnx("all %d possible files exist already.", MAX_NO_LOGFILE);
return -1;
int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC);
if (fd < 0) {
warn("failed opening log: %s", log_file_name);
mavlink_log_info(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
} else {
warnx("log file: %s", log_file_name);
mavlink_log_info(mavlink_fd, "[sdlog2] log file: %s", log_file_name);
}
return 0;
return fd;
}
static void *logwriter_thread(void *arg)
@ -363,9 +400,12 @@ static void *logwriter_thread(void *arg)
/* set name */
prctl(PR_SET_NAME, "sdlog2_writer", 0);
struct logbuffer_s *logbuf = (struct logbuffer_s *)arg;
int log_fd = open_log_file();
int log_fd = open_logfile();
if (log_fd < 0)
return;
struct logbuffer_s *logbuf = (struct logbuffer_s *)arg;
/* write log messages formats, version and parameters */
log_bytes_written += write_formats(log_fd);
@ -443,14 +483,20 @@ static void *logwriter_thread(void *arg)
fsync(log_fd);
close(log_fd);
return OK;
return;
}
void sdlog2_start_log()
{
warnx("start logging.");
warnx("start logging");
mavlink_log_info(mavlink_fd, "[sdlog2] start logging");
/* create log dir if needed */
if (create_log_dir() != 0) {
mavlink_log_critical(mavlink_fd, "[sdlog2] error creating log dir");
errx(1, "error creating log dir");
}
/* initialize statistics counter */
log_bytes_written = 0;
start_time = hrt_absolute_time();
@ -458,30 +504,28 @@ void sdlog2_start_log()
log_msgs_skipped = 0;
/* initialize log buffer emptying thread */
pthread_attr_t receiveloop_attr;
pthread_attr_init(&receiveloop_attr);
pthread_attr_init(&logwriter_attr);
struct sched_param param;
/* low priority, as this is expensive disk I/O */
param.sched_priority = SCHED_PRIORITY_DEFAULT - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
(void)pthread_attr_setschedparam(&logwriter_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 2048);
pthread_attr_setstacksize(&logwriter_attr, 2048);
logwriter_should_exit = false;
/* start log buffer emptying thread */
if (0 != pthread_create(&logwriter_pthread, &receiveloop_attr, logwriter_thread, &lb)) {
if (0 != pthread_create(&logwriter_pthread, &logwriter_attr, logwriter_thread, &lb)) {
errx(1, "error creating logwriter thread");
}
logging_enabled = true;
// XXX we have to destroy the attr at some point
}
void sdlog2_stop_log()
{
warnx("stop logging.");
warnx("stop logging");
mavlink_log_info(mavlink_fd, "[sdlog2] stop logging");
logging_enabled = false;
@ -501,6 +545,7 @@ void sdlog2_stop_log()
}
logwriter_pthread = 0;
pthread_attr_destroy(&logwriter_attr);
sdlog2_status();
}
@ -569,8 +614,8 @@ int write_parameters(int fd)
}
case PARAM_TYPE_FLOAT:
param_get(param, &value);
break;
param_get(param, &value);
break;
default:
break;
@ -588,18 +633,25 @@ int sdlog2_thread_main(int argc, char *argv[])
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
if (mavlink_fd < 0) {
warnx("failed to open MAVLink log stream, start mavlink app first.");
warnx("failed to open MAVLink log stream, start mavlink app first");
}
/* log buffer size */
int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT;
logging_enabled = false;
log_on_start = false;
log_when_armed = false;
log_name_timestamp = false;
flag_system_armed = false;
/* work around some stupidity in task_create's argv handling */
argc -= 2;
argv += 2;
int ch;
while ((ch = getopt(argc, argv, "r:b:ea")) != EOF) {
while ((ch = getopt(argc, argv, "r:b:eat")) != EOF) {
switch (ch) {
case 'r': {
unsigned long r = strtoul(optarg, NULL, 10);
@ -632,49 +684,52 @@ int sdlog2_thread_main(int argc, char *argv[])
log_when_armed = true;
break;
case 't':
log_name_timestamp = true;
break;
case '?':
if (optopt == 'c') {
warnx("Option -%c requires an argument.", optopt);
warnx("option -%c requires an argument", optopt);
} else if (isprint(optopt)) {
warnx("Unknown option `-%c'.", optopt);
warnx("unknown option `-%c'", optopt);
} else {
warnx("Unknown option character `\\x%x'.", optopt);
warnx("unknown option character `\\x%x'", optopt);
}
default:
sdlog2_usage("unrecognized flag");
errx(1, "exiting.");
errx(1, "exiting");
}
}
if (!file_exist(mountpoint)) {
errx(1, "logging mount point %s not present, exiting.", mountpoint);
}
if (create_logfolder()) {
errx(1, "unable to create logging folder, exiting.");
gps_time = 0;
/* create log root dir */
int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO);
if (mkdir_ret != 0 && errno != EEXIST) {
err("failed creating log root dir: %s", log_root);
}
/* copy conversion scripts */
const char *converter_in = "/etc/logging/conv.zip";
char *converter_out = malloc(120);
sprintf(converter_out, "%s/conv.zip", folder_path);
char *converter_out = malloc(64);
snprintf(converter_out, 64, "%s/conv.zip", log_root);
if (file_copy(converter_in, converter_out)) {
errx(1, "unable to copy conversion scripts, exiting.");
if (file_copy(converter_in, converter_out) != OK) {
warn("unable to copy conversion scripts");
}
free(converter_out);
/* only print logging path, important to find log file later */
warnx("logging to directory: %s", folder_path);
/* initialize log buffer with specified size */
warnx("log buffer size: %i bytes.", log_buffer_size);
warnx("log buffer size: %i bytes", log_buffer_size);
if (OK != logbuffer_init(&lb, log_buffer_size)) {
errx(1, "can't allocate log buffer, exiting.");
errx(1, "can't allocate log buffer, exiting");
}
struct vehicle_status_s buf_status;
@ -895,7 +950,7 @@ int sdlog2_thread_main(int argc, char *argv[])
* differs from the number of messages in the above list.
*/
if (fdsc_count > fdsc) {
warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.", __FILE__, __LINE__);
warn("WARNING: Not enough space for poll fds allocated. Check %s:%d", __FILE__, __LINE__);
fdsc_count = fdsc;
}
@ -919,19 +974,27 @@ int sdlog2_thread_main(int argc, char *argv[])
uint16_t differential_pressure_counter = 0;
/* enable logging on start if needed */
if (log_on_start)
if (log_on_start) {
/* check GPS topic to get GPS time */
if (log_name_timestamp) {
if (OK == orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos)) {
gps_time = buf.gps_pos.time_gps_usec;
}
}
sdlog2_start_log();
}
while (!main_thread_should_exit) {
/* decide use usleep() or blocking poll() */
bool use_sleep = sleep_delay > 0 && logging_enabled;
/* poll all topics if logging enabled or only management (first 2) if not */
int poll_ret = poll(fds, logging_enabled ? fdsc_count : 2, use_sleep ? 0 : poll_timeout);
int poll_ret = poll(fds, logging_enabled ? fdsc_count : 3, use_sleep ? 0 : poll_timeout);
/* handle the poll result */
if (poll_ret < 0) {
warnx("ERROR: poll error, stop logging.");
warnx("ERROR: poll error, stop logging");
main_thread_should_exit = true;
} else if (poll_ret > 0) {
@ -960,6 +1023,17 @@ int sdlog2_thread_main(int argc, char *argv[])
handled_topics++;
}
/* --- GPS POSITION - LOG MANAGEMENT --- */
if (fds[ifds++].revents & POLLIN) {
orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
if (log_name_timestamp) {
gps_time = buf.gps_pos.time_gps_usec;
}
handled_topics++;
}
if (!logging_enabled || !check_data || handled_topics >= poll_ret) {
continue;
}
@ -988,7 +1062,7 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- GPS POSITION --- */
if (fds[ifds++].revents & POLLIN) {
orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
// Don't orb_copy, it's already done few lines above
log_msg.msg_type = LOG_GPS_MSG;
log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec;
log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type;
@ -1279,7 +1353,7 @@ int sdlog2_thread_main(int argc, char *argv[])
free(lb.data);
warnx("exiting.");
warnx("exiting");
thread_running = false;
@ -1292,8 +1366,8 @@ void sdlog2_status()
float mebibytes = kibibytes / 1024.0f;
float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f;
warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs.", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs.", log_msgs_written, log_msgs_skipped);
warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped);
}
/**
@ -1312,7 +1386,7 @@ int file_copy(const char *file_old, const char *file_new)
int ret = 0;
if (source == NULL) {
warnx("failed opening input file to copy.");
warnx("failed opening input file to copy");
return 1;
}
@ -1320,7 +1394,7 @@ int file_copy(const char *file_old, const char *file_new)
if (target == NULL) {
fclose(source);
warnx("failed to open output file to copy.");
warnx("failed to open output file to copy");
return 1;
}
@ -1331,7 +1405,7 @@ int file_copy(const char *file_old, const char *file_new)
ret = fwrite(buf, 1, nread, target);
if (ret <= 0) {
warnx("error writing file.");
warnx("error writing file");
ret = 1;
break;
}

View File

@ -1548,8 +1548,8 @@ Sensors::task_main()
raw.adc_voltage_v[3] = 0.0f;
memset(&_battery_status, 0, sizeof(_battery_status));
_battery_status.voltage_v = 0.0f;
_battery_status.voltage_filtered_v = 0.0f;
_battery_status.voltage_v = -1.0f;
_battery_status.voltage_filtered_v = -1.0f;
_battery_status.current_a = -1.0f;
_battery_status.discharged_mah = -1.0f;

View File

@ -0,0 +1,73 @@
/****************************************************************************
*
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file hw_ver.c
*
* Show and test hardware version.
*/
#include <nuttx/config.h>
#include <stdio.h>
#include <string.h>
#include <errno.h>
#include <version/version.h>
__EXPORT int hw_ver_main(int argc, char *argv[]);
int
hw_ver_main(int argc, char *argv[])
{
if (argc >= 2) {
if (!strcmp(argv[1], "show")) {
printf(HW_ARCH "\n");
exit(0);
}
if (!strcmp(argv[1], "compare")) {
if (argc >= 3) {
int ret = strcmp(HW_ARCH, argv[2]) != 0;
if (ret == 0) {
printf("hw_ver match: %s\n", HW_ARCH);
}
exit(ret);
} else {
errx(1, "not enough arguments, try 'compare PX4FMU_1'");
}
}
}
errx(1, "expected a command, try 'show' or 'compare'");
}

View File

@ -0,0 +1,43 @@
############################################################################
#
# Copyright (c) 2014 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Show and test hardware version
#
MODULE_COMMAND = hw_ver
SRCS = hw_ver.c
MODULE_STACKSIZE = 1024
MAXOPTIMIZATION = -Os