forked from Archive/PX4-Autopilot
Merge remote-tracking branch 'px4/master' into bottle_drop
Conflicts: ROMFS/px4fmu_common/init.d/rcS
This commit is contained in:
commit
873fa4cb40
|
@ -35,3 +35,4 @@ mavlink/include/mavlink/v0.9/
|
|||
/Documentation/doxygen*objdb*tmp
|
||||
.tags
|
||||
.tags_sorted_by_file
|
||||
.pydevproject
|
||||
|
|
|
@ -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
|
||||
|
|
Binary file not shown.
After Width: | Height: | Size: 17 KiB |
|
@ -1,57 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set MC_ATTRATE_D 0
|
||||
param set MC_ATTRATE_I 0
|
||||
param set MC_ATTRATE_P 0.13
|
||||
param set MC_ATT_D 0
|
||||
param set MC_ATT_I 0.3
|
||||
param set MC_ATT_P 5
|
||||
param set MC_YAWPOS_D 0.1
|
||||
param set MC_YAWPOS_I 0.15
|
||||
param set MC_YAWPOS_P 1
|
||||
param set MC_YAWRATE_D 0
|
||||
param set MC_YAWRATE_I 0
|
||||
param set MC_YAWRATE_P 0.15
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
param set BAT_V_SCALING 0.008381
|
||||
|
||||
#
|
||||
# Start MAVLink
|
||||
#
|
||||
mavlink start -d /dev/ttyS0 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Configure PX4FMU for operation with PX4IOAR
|
||||
#
|
||||
fmu mode_gpio_serial
|
||||
|
||||
#
|
||||
# Fire up the AR.Drone interface.
|
||||
#
|
||||
ardrone_interface start -d /dev/ttyS1
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
# Exit, because /dev/ttyS0 is needed for MAVLink
|
||||
exit
|
|
@ -1,88 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set MC_ATTRATE_D 0
|
||||
param set MC_ATTRATE_I 0
|
||||
param set MC_ATTRATE_P 0.13
|
||||
param set MC_ATT_D 0
|
||||
param set MC_ATT_I 0.3
|
||||
param set MC_ATT_P 5
|
||||
param set MC_YAWPOS_D 0.1
|
||||
param set MC_YAWPOS_I 0.15
|
||||
param set MC_YAWPOS_P 1
|
||||
param set MC_YAWRATE_D 0
|
||||
param set MC_YAWRATE_I 0
|
||||
param set MC_YAWRATE_P 0.15
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
param set BAT_V_SCALING 0.008381
|
||||
|
||||
#
|
||||
# Start MAVLink and MAVLink Onboard (PX4FLOW Sensor)
|
||||
#
|
||||
mavlink start -d /dev/ttyS0 -b 57600
|
||||
mavlink_onboard start -d /dev/ttyS3 -b 115200
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Configure PX4FMU for operation with PX4IOAR
|
||||
#
|
||||
fmu mode_gpio_serial
|
||||
|
||||
#
|
||||
# Fire up the AR.Drone interface.
|
||||
#
|
||||
ardrone_interface start -d /dev/ttyS1
|
||||
|
||||
#
|
||||
# Start the sensors.
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start the commander.
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Start the position estimator
|
||||
#
|
||||
flow_position_estimator start
|
||||
|
||||
#
|
||||
# Fire up the multi rotor attitude controller
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Fire up the flow position controller
|
||||
#
|
||||
flow_position_control start
|
||||
|
||||
#
|
||||
# Fire up the flow speed controller
|
||||
#
|
||||
flow_speed_control start
|
||||
|
||||
# Exit, because /dev/ttyS0 is needed for MAVLink
|
||||
exit
|
|
@ -1,87 +1,14 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HILStar / X-Plane
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting.."
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
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 100
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.65
|
||||
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_Y_ROLLFF 1.1
|
||||
param set FW_L1_PERIOD 16
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
echo "HIL Rascal 110 starting.."
|
||||
|
||||
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
|
||||
|
||||
#
|
||||
# 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 MIXER FMU_AERT
|
||||
|
|
|
@ -0,0 +1,29 @@
|
|||
#!nsh
|
||||
#
|
||||
# Team Blacksheep Discovery Quadcopter
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>, Simon Wilks <sjwilks@gmail.com>, Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# TODO review MC_YAWRATE_I
|
||||
param set MC_ROLL_P 8.0
|
||||
param set MC_ROLLRATE_P 0.07
|
||||
param set MC_ROLLRATE_I 0.05
|
||||
param set MC_ROLLRATE_D 0.0017
|
||||
param set MC_PITCH_P 8.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.1
|
||||
param set MC_PITCHRATE_D 0.0025
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.28
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
set MIXER FMU_quad_w
|
||||
|
||||
set PWM_OUTPUTS 1234
|
|
@ -0,0 +1,32 @@
|
|||
#!nsh
|
||||
#
|
||||
# 3DR Iris Quadcopter
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# TODO tune roll/pitch separately
|
||||
param set MC_ROLL_P 9.0
|
||||
param set MC_ROLLRATE_P 0.13
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.004
|
||||
param set MC_PITCH_P 9.0
|
||||
param set MC_PITCHRATE_P 0.13
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.004
|
||||
param set MC_YAW_P 0.5
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
|
||||
param set BAT_V_SCALING 0.00989
|
||||
param set BAT_C_SCALING 0.0124
|
||||
fi
|
||||
|
||||
set MIXER FMU_quad_w
|
||||
|
||||
set PWM_OUTPUTS 1234
|
|
@ -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"
|
||||
|
|
@ -0,0 +1,12 @@
|
|||
#!nsh
|
||||
#
|
||||
# HIL Quadcopter X
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER FMU_quad_x
|
||||
|
||||
set HIL yes
|
|
@ -1,79 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting in state-HIL mode.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
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 100
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.65
|
||||
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_Y_ROLLFF 1.1
|
||||
|
||||
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"
|
||||
|
|
@ -1,105 +1,12 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HIL Quadcopter +
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
echo "[HIL] HILS quadrotor + starting.."
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
#
|
||||
# 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
|
||||
#
|
||||
multirotor_pos_control start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
set MIXER FMU_quad_+
|
||||
|
||||
set HIL yes
|
|
@ -1,98 +1,14 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HIL Rascal 110 (Flightgear)
|
||||
#
|
||||
# Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting.."
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
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 100
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.65
|
||||
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_Y_ROLLFF 1.1
|
||||
param set FW_L1_PERIOD 16
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
echo "HIL Rascal 110 starting.."
|
||||
|
||||
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
|
||||
|
||||
#
|
||||
# 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 HIL yes
|
||||
|
||||
set MIXER FMU_AERT
|
||||
|
|
|
@ -0,0 +1,47 @@
|
|||
#!nsh
|
||||
#
|
||||
# HIL Malolo 1 (Flightgear)
|
||||
#
|
||||
# Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MIN 12
|
||||
param set FW_AIRSPD_TRIM 25
|
||||
param set FW_AIRSPD_MAX 40
|
||||
param set FW_ATT_TC 0.3
|
||||
param set FW_L1_DAMPING 0.74
|
||||
param set FW_L1_PERIOD 15
|
||||
param set FW_PR_FF 0.8
|
||||
param set FW_PR_I 0.05
|
||||
param set FW_PR_IMAX 0.2
|
||||
param set FW_PR_P 0.1
|
||||
param set FW_P_ROLLFF 0
|
||||
param set FW_RR_FF 0.6
|
||||
param set FW_RR_I 0.02
|
||||
param set FW_RR_IMAX 0.2
|
||||
param set FW_RR_P 0.1
|
||||
param set FW_R_LIM 45
|
||||
param set FW_R_RMAX 0
|
||||
param set FW_T_CLMB_MAX 5
|
||||
param set FW_T_HRATE_P 0.02
|
||||
param set FW_T_PTCH_DAMP 0
|
||||
param set FW_T_RLL2THR 15
|
||||
param set FW_T_SINK_MAX 5
|
||||
param set FW_T_SINK_MIN 2
|
||||
param set FW_T_SRATE_P 0.01
|
||||
param set FW_T_TIME_CONST 3
|
||||
param set FW_T_VERT_ACC 7
|
||||
param set FW_YR_FF 0.0
|
||||
param set FW_YR_I 0
|
||||
param set FW_YR_IMAX 0.2
|
||||
param set FW_YR_P 0.0
|
||||
fi
|
||||
|
||||
set HIL yes
|
||||
|
||||
# Set the AERT mixer for HIL (even if the malolo is a flying wing)
|
||||
set MIXER FMU_AERT
|
|
@ -1,87 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
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 100
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.65
|
||||
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_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
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,87 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on HK Bixler"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
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 100
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.65
|
||||
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_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
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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_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_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,89 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
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 100
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.65
|
||||
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_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
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
pwm disarmed -c 3 -p 1056
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
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_AETR.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AETR.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,97 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
|
||||
|
||||
#
|
||||
# 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 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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 (for DJI ESCs)
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1200
|
||||
pwm max -c 1234 -p 1800
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
#
|
||||
sh /etc/init.d/rc.multirotor
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -0,0 +1,15 @@
|
|||
#!nsh
|
||||
#
|
||||
# UNTESTED UNTESTED!
|
||||
#
|
||||
# Generic 10” Hexa coaxial geometry
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER hexa_cox
|
||||
|
||||
# We only can run one channel group with one rate, so set all 8 channels
|
||||
set PWM_OUTPUTS 12345678
|
|
@ -1,83 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on DJI F450"
|
||||
|
||||
#
|
||||
# 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 save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
commander start
|
||||
|
||||
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 (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
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,98 +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 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_hex_x.mix
|
||||
|
||||
#
|
||||
# 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
|
|
@ -0,0 +1,12 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo coaxial geometry
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER octo_cox
|
||||
|
||||
set PWM_OUTPUTS 12345678
|
|
@ -1,81 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] Team Blacksheep Discovery Quad"
|
||||
|
||||
#
|
||||
# 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.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
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,80 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] 3DR Iris Quad"
|
||||
|
||||
#
|
||||
# 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.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
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -0,0 +1,8 @@
|
|||
#!nsh
|
||||
#
|
||||
# MPX EasyStar Plane
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_RET
|
|
@ -0,0 +1,5 @@
|
|||
#!nsh
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_AERT
|
|
@ -0,0 +1,5 @@
|
|||
#!nsh
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_AERT
|
|
@ -0,0 +1,5 @@
|
|||
#!nsh
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_Q
|
|
@ -0,0 +1,10 @@
|
|||
#!nsh
|
||||
#
|
||||
# Phantom FPV Flying Wing
|
||||
#
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_Q
|
|
@ -0,0 +1,39 @@
|
|||
#!nsh
|
||||
#
|
||||
# Skywalker X5 Flying Wing
|
||||
#
|
||||
# Thomas Gubler <thomasgubler@gmail.com>, Julian Oes <joes@student.ethz.ch>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MIN 15
|
||||
param set FW_AIRSPD_TRIM 20
|
||||
param set FW_AIRSPD_MAX 40
|
||||
param set FW_ATT_TC 0.3
|
||||
param set FW_L1_DAMPING 0.74
|
||||
param set FW_L1_PERIOD 15
|
||||
param set FW_PR_FF 0.3
|
||||
param set FW_PR_I 0
|
||||
param set FW_PR_IMAX 0.2
|
||||
param set FW_PR_P 0.03
|
||||
param set FW_P_LIM_MAX 45
|
||||
param set FW_P_LIM_MIN -45
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 0
|
||||
param set FW_RR_FF 0.3
|
||||
param set FW_RR_I 0
|
||||
param set FW_RR_IMAX 0.2
|
||||
param set FW_RR_P 0.03
|
||||
param set FW_R_LIM 60
|
||||
param set FW_R_RMAX 0
|
||||
param set FW_T_HRATE_P 0.01
|
||||
param set FW_T_RLL2THR 15
|
||||
param set FW_T_SRATE_P 0.01
|
||||
param set FW_T_TIME_CONST 5
|
||||
fi
|
||||
|
||||
set MIXER FMU_X5
|
|
@ -0,0 +1,10 @@
|
|||
#!nsh
|
||||
#
|
||||
# Wing Wing (aka Z-84) Flying Wing
|
||||
#
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_Q
|
|
@ -0,0 +1,10 @@
|
|||
#!nsh
|
||||
#
|
||||
# FX-79 Buffalo Flying Wing
|
||||
#
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_FX79
|
|
@ -1,65 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"
|
||||
|
||||
#
|
||||
# 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 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,87 +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_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 100
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.65
|
||||
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_Y_ROLLFF 1.1
|
||||
param set FW_L1_PERIOD 17
|
||||
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
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,65 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Skywalker X5"
|
||||
|
||||
#
|
||||
# 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 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -0,0 +1,12 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Quad X geometry
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER FMU_quad_x
|
||||
|
||||
set PWM_OUTPUTS 1234
|
|
@ -0,0 +1,35 @@
|
|||
#!nsh
|
||||
#
|
||||
# ARDrone
|
||||
#
|
||||
|
||||
echo "[init] 4008_ardrone: PX4FMU on PX4IOAR carrier board"
|
||||
|
||||
# Just use the default multicopter settings.
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set MC_ROLL_P 5.0
|
||||
param set MC_ROLLRATE_P 0.13
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.0
|
||||
param set MC_PITCH_P 5.0
|
||||
param set MC_PITCHRATE_P 0.13
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.0
|
||||
param set MC_YAW_P 1.0
|
||||
param set MC_YAW_D 0.1
|
||||
param set MC_YAWRATE_P 0.15
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.15
|
||||
fi
|
||||
|
||||
set OUTPUT_MODE ardrone
|
||||
set USE_IO no
|
||||
set MIXER skip
|
|
@ -0,0 +1,27 @@
|
|||
#!nsh
|
||||
#
|
||||
# DJI Flame Wheel F330 Quadcopter
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
set PWM_MIN 1175
|
||||
set PWM_MAX 1900
|
|
@ -0,0 +1,28 @@
|
|||
#!nsh
|
||||
#
|
||||
# DJI Flame Wheel F450 Quadcopter
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# TODO REVIEW
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
set PWM_MIN 1175
|
||||
set PWM_MAX 1900
|
|
@ -1,56 +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 commander (depends on orb, mavlink)
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# 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
|
|
@ -0,0 +1,12 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Quad + geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER FMU_quad_+
|
||||
|
||||
set PWM_OUTPUTS 1234
|
|
@ -0,0 +1,13 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Hexa X geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER FMU_hexa_x
|
||||
|
||||
# We only can run one channel group with one rate, so set all 8 channels
|
||||
set PWM_OUTPUTS 12345678
|
|
@ -1,83 +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
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -0,0 +1,13 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Hexa + geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER FMU_hexa_+
|
||||
|
||||
# We only can run one channel group with one rate, so set all 8 channels
|
||||
set PWM_OUTPUTS 12345678
|
|
@ -0,0 +1,12 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo X geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER FMU_octo_x
|
||||
|
||||
set PWM_OUTPUTS 12345678
|
|
@ -0,0 +1,12 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo + geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER FMU_octo_+
|
||||
|
||||
set PWM_OUTPUTS 12345678
|
|
@ -1,75 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] bottle drop test
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 2 = quadrotor
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
set EXIT_ON_END no
|
||||
|
||||
#
|
||||
# Start and configure PX4IO and FMU interface
|
||||
#
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the sensors and test them.
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start logging (depends on sensors)
|
||||
#
|
||||
#sh /etc/init.d/rc.logging
|
||||
sdlog2 start -r 200 -e -b 16
|
||||
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Start position estimator
|
||||
#
|
||||
position_estimator_inav start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
|
||||
fmu mode_pwm
|
||||
|
||||
mixer load /dev/px4fmu /etc/mixers/FMU_pass.mix
|
||||
|
||||
pwm min -d /dev/px4fmu -c 123 -p 900
|
||||
pwm max -d /dev/px4fmu -c 123 -p 2100
|
||||
|
||||
pwm arm -d /dev/px4fmu
|
||||
|
||||
bottle_drop start
|
||||
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
exit
|
||||
fi
|
|
@ -1,91 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
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 100
|
||||
param set FW_R_RMAX 100
|
||||
param set FW_THR_CRUISE 0.65
|
||||
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_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
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
#
|
||||
# Start IO
|
||||
#
|
||||
px4io start
|
||||
|
||||
|
||||
mixer load /dev/px4io /etc/mixers/FMU_pass.mix
|
||||
|
||||
pwm min -d /dev/px4io -c 123 -p 900
|
||||
pwm max -d /dev/px4io -c 123 -p 2100
|
||||
|
||||
pwm arm -d /dev/px4io
|
||||
|
||||
bottle_drop start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
|
|
@ -1,9 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
cp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded
|
||||
if cmp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded
|
||||
then
|
||||
echo "CMP returned true"
|
||||
else
|
||||
echo "CMP returned false"
|
||||
fi
|
|
@ -0,0 +1,203 @@
|
|||
#
|
||||
# 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 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
|
||||
|
||||
if param compare SYS_AUTOSTART 1005
|
||||
then
|
||||
sh /etc/init.d/1005_rc_fw_Malolo1.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 30
|
||||
then
|
||||
sh /etc/init.d/3030_io_camflyer
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3031 31
|
||||
then
|
||||
sh /etc/init.d/3031_phantom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3032 32
|
||||
then
|
||||
sh /etc/init.d/3032_skywalker_x5
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3033 33
|
||||
then
|
||||
sh /etc/init.d/3033_wingwing
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 3034 34
|
||||
then
|
||||
sh /etc/init.d/3034_fx79
|
||||
fi
|
||||
|
||||
#
|
||||
# Quad X
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 4001
|
||||
then
|
||||
sh /etc/init.d/4001_quad_x
|
||||
fi
|
||||
|
||||
#
|
||||
# ARDrone
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 4008 8
|
||||
then
|
||||
sh /etc/init.d/4008_ardrone
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4010 10
|
||||
then
|
||||
sh /etc/init.d/4010_dji_f330
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4011 11
|
||||
then
|
||||
sh /etc/init.d/4011_dji_f450
|
||||
fi
|
||||
|
||||
#
|
||||
# Quad +
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 5001
|
||||
then
|
||||
sh /etc/init.d/5001_quad_+
|
||||
fi
|
||||
|
||||
#
|
||||
# Hexa X
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 6001
|
||||
then
|
||||
sh /etc/init.d/6001_hexa_x
|
||||
fi
|
||||
|
||||
#
|
||||
# Hexa +
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 7001
|
||||
then
|
||||
sh /etc/init.d/7001_hexa_+
|
||||
fi
|
||||
|
||||
#
|
||||
# Octo X
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 8001
|
||||
then
|
||||
sh /etc/init.d/8001_octo_x
|
||||
fi
|
||||
|
||||
#
|
||||
# Octo +
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 9001
|
||||
then
|
||||
sh /etc/init.d/9001_octo_+
|
||||
fi
|
||||
|
||||
#
|
||||
# Wide arm / H frame
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 10015 15
|
||||
then
|
||||
sh /etc/init.d/10015_tbs_discovery
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10016 16
|
||||
then
|
||||
sh /etc/init.d/10016_3dr_iris
|
||||
fi
|
||||
|
||||
#
|
||||
# Hexa Coaxial
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 11001
|
||||
then
|
||||
sh /etc/init.d/11001_hexa_cox
|
||||
fi
|
||||
|
||||
#
|
||||
# Octo Coaxial
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 12001
|
||||
then
|
||||
sh /etc/init.d/12001_octo_cox
|
||||
fi
|
|
@ -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
|
|
@ -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"
|
|
@ -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
|
|
@ -0,0 +1,8 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard apps for fixed wing
|
||||
#
|
||||
|
||||
att_pos_estimator_ekf start
|
||||
fw_att_control start
|
||||
fw_pos_control_l1 start
|
|
@ -0,0 +1,14 @@
|
|||
#!nsh
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for FW
|
||||
#
|
||||
param set NAV_LAND_ALT 90
|
||||
param set NAV_RTL_ALT 100
|
||||
param set NAV_RTL_LAND_T -1
|
||||
param set NAV_ACCEPT_RAD 50
|
||||
fi
|
|
@ -0,0 +1,75 @@
|
|||
#!nsh
|
||||
#
|
||||
# Script to configure control interface
|
||||
#
|
||||
|
||||
if [ $MIXER != none -a $MIXER != skip ]
|
||||
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
|
||||
if [ $MIXER != skip ]
|
||||
then
|
||||
echo "[init] Mixer not defined"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
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
|
|
@ -1,23 +1,20 @@
|
|||
#
|
||||
# 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.
|
||||
#
|
||||
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
|
||||
|
|
|
@ -1,14 +1,16 @@
|
|||
#!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
|
||||
echo "Start sdlog2 at 50Hz"
|
||||
sdlog2 start -r 50 -a -b 8 -t
|
||||
else
|
||||
sdlog2 start -r 200 -a -b 16
|
||||
echo "Start sdlog2 at 200Hz"
|
||||
sdlog2 start -r 200 -a -b 16 -t
|
||||
fi
|
||||
fi
|
||||
|
|
|
@ -0,0 +1,11 @@
|
|||
#!nsh
|
||||
#
|
||||
# Standard apps for multirotors:
|
||||
# att & pos estimator, att & pos control.
|
||||
#
|
||||
|
||||
attitude_estimator_ekf start
|
||||
position_estimator_inav start
|
||||
|
||||
mc_att_control start
|
||||
mc_pos_control start
|
|
@ -0,0 +1,43 @@
|
|||
#!nsh
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.5
|
||||
|
||||
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_P 0.1
|
||||
param set MPC_XY_VEL_I 0.02
|
||||
param set MPC_XY_VEL_D 0.01
|
||||
param set MPC_XY_VEL_MAX 5
|
||||
param set MPC_XY_FF 0.5
|
||||
param set MPC_Z_P 1.0
|
||||
param set MPC_Z_VEL_P 0.1
|
||||
param set MPC_Z_VEL_I 0.02
|
||||
param set MPC_Z_VEL_D 0.0
|
||||
param set MPC_Z_VEL_MAX 3
|
||||
param set MPC_Z_FF 0.5
|
||||
param set MPC_TILT_MAX 1.0
|
||||
param set MPC_LAND_SPEED 1.0
|
||||
param set MPC_LAND_TILT 0.3
|
||||
fi
|
||||
|
||||
set PWM_RATE 400
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1075
|
||||
set PWM_MAX 2000
|
|
@ -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
|
|
@ -3,48 +3,45 @@
|
|||
# Standard startup script for PX4FMU onboard sensor drivers.
|
||||
#
|
||||
|
||||
#
|
||||
# Start sensor drivers here.
|
||||
#
|
||||
|
||||
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
|
||||
|
|
|
@ -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"
|
|
@ -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
|
||||
|
|
|
@ -3,44 +3,44 @@
|
|||
# PX4FMU startup script.
|
||||
|
||||
#
|
||||
# Default to auto-start mode. An init script on the microSD card
|
||||
# can change this to prevent automatic startup of the flight script.
|
||||
# Default to auto-start mode.
|
||||
#
|
||||
set MODE autostart
|
||||
|
||||
set logfile /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"
|
||||
set LOG_FILE /fs/microsd/bootlog.txt
|
||||
echo "[init] microSD card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
set LOG_FILE /dev/null
|
||||
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,84 +72,146 @@ then
|
|||
uorb start
|
||||
|
||||
#
|
||||
# Load microSD params
|
||||
# Load parameters
|
||||
#
|
||||
#if ramtron start
|
||||
#then
|
||||
# param select /ramtron/params
|
||||
# if [ -f /ramtron/params ]
|
||||
# then
|
||||
# param load /ramtron/params
|
||||
# fi
|
||||
#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
|
||||
#fi
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
if mtd start
|
||||
then
|
||||
set PARAM_FILE /fs/mtd_params
|
||||
fi
|
||||
|
||||
param select $PARAM_FILE
|
||||
if param load
|
||||
then
|
||||
echo "[init] Parameters loaded: $PARAM_FILE"
|
||||
else
|
||||
echo "[init] ERROR: Parameters loading failed: $PARAM_FILE"
|
||||
fi
|
||||
|
||||
#
|
||||
# Start system state indicator
|
||||
#
|
||||
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
|
||||
|
||||
#
|
||||
# Start the Commander (needs to be this early for in-air-restarts)
|
||||
# Set default values
|
||||
#
|
||||
commander start
|
||||
|
||||
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
|
||||
|
||||
#
|
||||
# Start the datamanager
|
||||
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
|
||||
#
|
||||
dataman start
|
||||
|
||||
#
|
||||
# Start the Navigator
|
||||
#
|
||||
navigator start
|
||||
|
||||
if param compare SYS_AUTOSTART 1000
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
sh /etc/init.d/1000_rc_fw_easystar.hil
|
||||
set MODE custom
|
||||
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
|
||||
|
||||
if param compare SYS_AUTOSTART 1001
|
||||
then
|
||||
sh /etc/init.d/1001_rc_quad.hil
|
||||
set MODE custom
|
||||
fi
|
||||
set IO_PRESENT no
|
||||
|
||||
if param compare SYS_AUTOSTART 1002
|
||||
if [ $USE_IO == yes ]
|
||||
then
|
||||
sh /etc/init.d/1002_rc_fw_state.hil
|
||||
set MODE custom
|
||||
fi
|
||||
#
|
||||
# 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
|
||||
|
||||
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
|
||||
set IO_PRESENT yes
|
||||
else
|
||||
echo "[init] Trying to update"
|
||||
echo "PX4IO Trying to update" >> $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
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
else
|
||||
echo "[init] ERROR: PX4IO update failed"
|
||||
echo "PX4IO update failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $IO_PRESENT == no ]
|
||||
then
|
||||
echo "[init] ERROR: PX4IO not found"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 901
|
||||
|
@ -159,251 +220,337 @@ then
|
|||
set MODE custom
|
||||
fi
|
||||
|
||||
if [ $MODE != custom ]
|
||||
#
|
||||
# Set default output if not set
|
||||
#
|
||||
if [ $OUTPUT_MODE == none ]
|
||||
then
|
||||
# Try to get an USB console
|
||||
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 [ $OUTPUT_MODE == ardrone ]
|
||||
then
|
||||
set FMU_MODE gpio_serial
|
||||
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
|
||||
|
||||
#
|
||||
# Upgrade PX4IO firmware
|
||||
#
|
||||
|
||||
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
|
||||
|
||||
if px4io checkcrc $io_file
|
||||
#
|
||||
# Start the Commander (needs to be this early for in-air-restarts)
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start primary output
|
||||
#
|
||||
set TTYS1_BUSY no
|
||||
|
||||
# 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 200000
|
||||
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
|
||||
sh /etc/init.d/rc.error
|
||||
echo "[init] ERROR: PX4IO start failed"
|
||||
tone_alarm $TUNE_OUT_ERROR
|
||||
fi
|
||||
else
|
||||
echo "PX4IO update failed"
|
||||
echo "PX4IO update failed" >> $logfile
|
||||
tone_alarm MNGGG
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Check if auto-setup from one of the standard scripts is wanted
|
||||
# SYS_AUTOSTART = 0 means no autostart (default)
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 8
|
||||
then
|
||||
sh /etc/init.d/08_ardrone
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 9
|
||||
then
|
||||
sh /etc/init.d/09_ardrone_flow
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10
|
||||
then
|
||||
sh /etc/init.d/10_dji_f330
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 11
|
||||
then
|
||||
sh /etc/init.d/11_dji_f450
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 12
|
||||
then
|
||||
set MIXER /etc/mixers/FMU_hex_x.mix
|
||||
sh /etc/init.d/12-13_hex
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 13
|
||||
then
|
||||
set MIXER /etc/mixers/FMU_hex_+.mix
|
||||
sh /etc/init.d/12-13_hex
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 15
|
||||
then
|
||||
sh /etc/init.d/15_tbs_discovery
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 16
|
||||
then
|
||||
sh /etc/init.d/16_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 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 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 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 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 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 22
|
||||
then
|
||||
set FRAME_GEOMETRY w
|
||||
sh /etc/init.d/rc.custom_io_esc
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 30
|
||||
then
|
||||
sh /etc/init.d/30_io_camflyer
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 31
|
||||
then
|
||||
sh /etc/init.d/31_io_phantom
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 32
|
||||
then
|
||||
sh /etc/init.d/32_skywalker_x5
|
||||
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 100
|
||||
then
|
||||
sh /etc/init.d/100_mpx_easystar
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 101
|
||||
then
|
||||
sh /etc/init.d/101_hk_bixler
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 102
|
||||
then
|
||||
sh /etc/init.d/102_3dr_skywalker
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 900
|
||||
then
|
||||
sh /etc/init.d/900_bottle_drop_test
|
||||
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
|
||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
|
||||
then
|
||||
px4io start
|
||||
else
|
||||
if fmu mode_serial
|
||||
echo "[init] Use FMU as primary output"
|
||||
if fmu mode_$FMU_MODE
|
||||
then
|
||||
echo "FMU driver (no PWM) started"
|
||||
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 -o $OUTPUT_MODE == ardrone ]
|
||||
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_port2_pwm8
|
||||
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
|
||||
if [ $OUTPUT_MODE != fmu -a $OUTPUT_MODE != ardrone ]
|
||||
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
|
||||
|
||||
# Start sensors
|
||||
sh /etc/init.d/rc.sensors
|
||||
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 -o $OUTPUT_MODE == ardrone ]
|
||||
then
|
||||
set TTYS1_BUSY yes
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
# Start one of the estimators
|
||||
attitude_estimator_ekf start
|
||||
#
|
||||
# MAVLink
|
||||
#
|
||||
set EXIT_ON_END no
|
||||
|
||||
# Start GPS
|
||||
if [ $HIL == yes ]
|
||||
then
|
||||
sleep 1
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
usleep 5000
|
||||
else
|
||||
if [ $TTYS1_BUSY == yes ]
|
||||
then
|
||||
# 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
|
||||
# Start MAVLink on default port: ttyS1
|
||||
mavlink start
|
||||
usleep 5000
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the datamanager
|
||||
#
|
||||
dataman start
|
||||
|
||||
#
|
||||
# Start the navigator
|
||||
#
|
||||
navigator start
|
||||
|
||||
#
|
||||
# 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
|
||||
|
||||
#
|
||||
# Start up ARDrone Motor interface
|
||||
#
|
||||
if [ $OUTPUT_MODE == ardrone ]
|
||||
then
|
||||
ardrone_interface start -d /dev/ttyS1
|
||||
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
|
||||
echo "Default mixer for multicopter not defined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
# Use mixer to detect vehicle type
|
||||
if [ $MIXER == FMU_quad_x -o $MIXER == FMU_quad_+ ]
|
||||
then
|
||||
set MAV_TYPE 2
|
||||
fi
|
||||
if [ $MIXER == FMU_quad_w ]
|
||||
then
|
||||
set MAV_TYPE 2
|
||||
fi
|
||||
if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ]
|
||||
then
|
||||
set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == hexa_cox ]
|
||||
then
|
||||
set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == FMU_octo_x -o $MIXER == FMU_octo_+ ]
|
||||
then
|
||||
set MAV_TYPE 14
|
||||
fi
|
||||
if [ $MIXER == FMU_octo_cox ]
|
||||
then
|
||||
set MAV_TYPE 14
|
||||
fi
|
||||
fi
|
||||
|
||||
# Still no MAV_TYPE found
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
echo "Unknown MAV_TYPE"
|
||||
else
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
fi
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
|
||||
# Start standard multicopter apps
|
||||
sh /etc/init.d/rc.mc_apps
|
||||
fi
|
||||
|
||||
#
|
||||
# Generic setup (autostart ID not found)
|
||||
#
|
||||
if [ $VEHICLE_TYPE == none ]
|
||||
then
|
||||
echo "[init] Vehicle type: No autostart ID found"
|
||||
|
||||
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 ]
|
||||
then
|
||||
exit
|
||||
fi
|
||||
|
||||
# End of autostart
|
||||
|
|
Binary file not shown.
|
@ -0,0 +1,72 @@
|
|||
FX-79 Delta-wing mixer for PX4FMU
|
||||
=================================
|
||||
|
||||
Designed for FX-79.
|
||||
|
||||
TODO (sjwilks): Add mixers for flaps.
|
||||
|
||||
This file defines mixers suitable for controlling a delta wing aircraft using
|
||||
PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
|
||||
servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
|
||||
assumed to be unused.
|
||||
|
||||
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
|
||||
(roll), 1 (pitch) and 3 (thrust).
|
||||
|
||||
See the README for more information on the scaler format.
|
||||
|
||||
Elevon mixers
|
||||
-------------
|
||||
Three scalers total (output, roll, pitch).
|
||||
|
||||
On the assumption that the two elevon servos are physically reversed, the pitch
|
||||
input is inverted between the two servos.
|
||||
|
||||
The scaling factor for roll inputs is adjusted to implement differential travel
|
||||
for the elevons.
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 5000 8000 0 -10000 10000
|
||||
S: 0 1 8000 8000 0 -10000 10000
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 8000 5000 0 -10000 10000
|
||||
S: 0 1 -8000 -8000 0 -10000 10000
|
||||
|
||||
Output 2
|
||||
--------
|
||||
This mixer is empty.
|
||||
|
||||
Z:
|
||||
|
||||
Motor speed mixer
|
||||
-----------------
|
||||
Two scalers total (output, thrust).
|
||||
|
||||
This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
|
||||
range. Inputs below zero are treated as zero.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
|
||||
Gimbal / flaps / payload mixer for last four channels
|
||||
-----------------------------------------------------
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 4 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 5 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 6 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 7 10000 10000 0 -10000 10000
|
|
@ -25,13 +25,13 @@ for the elevons.
|
|||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -5000 -8000 0 -10000 10000
|
||||
S: 0 1 8000 8000 0 -10000 10000
|
||||
S: 0 0 -8000 -8000 0 -10000 10000
|
||||
S: 0 1 6000 6000 0 -10000 10000
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -8000 -5000 0 -10000 10000
|
||||
S: 0 1 -8000 -8000 0 -10000 10000
|
||||
S: 0 0 -8000 -8000 0 -10000 10000
|
||||
S: 0 1 -6000 -6000 0 -10000 10000
|
||||
|
||||
Output 2
|
||||
--------
|
||||
|
|
|
@ -23,13 +23,13 @@ for the elevons.
|
|||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -3000 -5000 0 -10000 10000
|
||||
S: 0 1 -5000 -5000 0 -10000 10000
|
||||
S: 0 0 -8000 -8000 0 -10000 10000
|
||||
S: 0 1 6000 6000 0 -10000 10000
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -5000 -3000 0 -10000 10000
|
||||
S: 0 1 5000 5000 0 -10000 10000
|
||||
S: 0 0 -8000 -8000 0 -10000 10000
|
||||
S: 0 1 -6000 -6000 0 -10000 10000
|
||||
|
||||
Output 2
|
||||
--------
|
||||
|
@ -48,7 +48,7 @@ M: 1
|
|||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
|
||||
Gimbal / payload mixer for last four channels
|
||||
Gimbal / flaps / payload mixer for last four channels
|
||||
-----------------------------------------------------
|
||||
|
||||
M: 1
|
||||
|
@ -66,4 +66,3 @@ S: 0 6 10000 10000 0 -10000 10000
|
|||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 7 10000 10000 0 -10000 10000
|
||||
|
||||
|
|
|
@ -1,18 +0,0 @@
|
|||
Multirotor mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
This file defines a single mixer for a hexacopter in the + configuration. All controls
|
||||
are mixed 100%.
|
||||
|
||||
R: 6+ 10000 10000 10000 0
|
||||
|
||||
Gimbal / payload mixer for last two channels
|
||||
-----------------------------------------------------
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 6 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 7 10000 10000 0 -10000 10000
|
|
@ -1,18 +0,0 @@
|
|||
Multirotor mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
This file defines a single mixer for a hexacopter in the X configuration. All controls
|
||||
are mixed 100%.
|
||||
|
||||
R: 6x 10000 10000 10000 0
|
||||
|
||||
Gimbal / payload mixer for last two channels
|
||||
-----------------------------------------------------
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 6 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 7 10000 10000 0 -10000 10000
|
|
@ -0,0 +1,3 @@
|
|||
# Hexa +
|
||||
|
||||
R: 6+ 10000 10000 10000 0
|
|
@ -0,0 +1,3 @@
|
|||
# Hexa X
|
||||
|
||||
R: 6x 10000 10000 10000 0
|
|
@ -1,7 +1,3 @@
|
|||
Multirotor mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
This file defines a single mixer for a octocopter in the + configuration. All controls
|
||||
are mixed 100%.
|
||||
# Octo +
|
||||
|
||||
R: 8+ 10000 10000 10000 0
|
||||
|
|
|
@ -1,7 +1,3 @@
|
|||
Multirotor mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
This file defines a single mixer for a Coaxial Octocopter in the X configuration. All controls
|
||||
are mixed 100%.
|
||||
# Octo coaxial
|
||||
|
||||
R: 8c 10000 10000 10000 0
|
||||
|
|
|
@ -1,7 +1,3 @@
|
|||
Multirotor mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
This file defines a single mixer for a octocopter in the X configuration. All controls
|
||||
are mixed 100%.
|
||||
# Octo X
|
||||
|
||||
R: 8x 10000 10000 10000 0
|
||||
|
|
|
@ -1,154 +0,0 @@
|
|||
PX4 mixer definitions
|
||||
=====================
|
||||
|
||||
Files in this directory implement example mixers that can be used as a basis
|
||||
for customisation, or for general testing purposes.
|
||||
|
||||
Mixer basics
|
||||
------------
|
||||
|
||||
Mixers combine control values from various sources (control tasks, user inputs,
|
||||
etc.) and produce output values suitable for controlling actuators; servos,
|
||||
motors, switches and so on.
|
||||
|
||||
An actuator derives its value from the combination of one or more control
|
||||
values. Each of the control values is scaled according to the actuator's
|
||||
configuration and then combined to produce the actuator value, which may then be
|
||||
further scaled to suit the specific output type.
|
||||
|
||||
Internally, all scaling is performed using floating point values. Inputs and
|
||||
outputs are clamped to the range -1.0 to 1.0.
|
||||
|
||||
control control control
|
||||
| | |
|
||||
v v v
|
||||
scale scale scale
|
||||
| | |
|
||||
| v |
|
||||
+-------> mix <------+
|
||||
|
|
||||
scale
|
||||
|
|
||||
v
|
||||
out
|
||||
|
||||
Scaling
|
||||
-------
|
||||
|
||||
Basic scalers provide linear scaling of the input to the output.
|
||||
|
||||
Each scaler allows the input value to be scaled independently for inputs
|
||||
greater/less than zero. An offset can be applied to the output, and lower and
|
||||
upper boundary constraints can be applied. Negative scaling factors cause the
|
||||
output to be inverted (negative input produces positive output).
|
||||
|
||||
Scaler pseudocode:
|
||||
|
||||
if (input < 0)
|
||||
output = (input * NEGATIVE_SCALE) + OFFSET
|
||||
else
|
||||
output = (input * POSITIVE_SCALE) + OFFSET
|
||||
|
||||
if (output < LOWER_LIMIT)
|
||||
output = LOWER_LIMIT
|
||||
if (output > UPPER_LIMIT)
|
||||
output = UPPER_LIMIT
|
||||
|
||||
Syntax
|
||||
------
|
||||
|
||||
Mixer definitions are text files; lines beginning with a single capital letter
|
||||
followed by a colon are significant. All other lines are ignored, meaning that
|
||||
explanatory text can be freely mixed with the definitions.
|
||||
|
||||
Each file may define more than one mixer; the allocation of mixers to actuators
|
||||
is specific to the device reading the mixer definition, and the number of
|
||||
actuator outputs generated by a mixer is specific to the mixer.
|
||||
|
||||
A mixer begins with a line of the form
|
||||
|
||||
<tag>: <mixer arguments>
|
||||
|
||||
The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
|
||||
multirotor mixer, etc.
|
||||
|
||||
Null Mixer
|
||||
..........
|
||||
|
||||
A null mixer consumes no controls and generates a single actuator output whose
|
||||
value is always zero. Typically a null mixer is used as a placeholder in a
|
||||
collection of mixers in order to achieve a specific pattern of actuator outputs.
|
||||
|
||||
The null mixer definition has the form:
|
||||
|
||||
Z:
|
||||
|
||||
Simple Mixer
|
||||
............
|
||||
|
||||
A simple mixer combines zero or more control inputs into a single actuator
|
||||
output. Inputs are scaled, and the mixing function sums the result before
|
||||
applying an output scaler.
|
||||
|
||||
A simple mixer definition begins with:
|
||||
|
||||
M: <control count>
|
||||
O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
|
||||
|
||||
If <control count> is zero, the sum is effectively zero and the mixer will
|
||||
output a fixed value that is <offset> constrained by <lower limit> and <upper
|
||||
limit>.
|
||||
|
||||
The second line defines the output scaler with scaler parameters as discussed
|
||||
above. Whilst the calculations are performed as floating-point operations, the
|
||||
values stored in the definition file are scaled by a factor of 10000; i.e. an
|
||||
offset of -0.5 is encoded as -5000.
|
||||
|
||||
The definition continues with <control count> entries describing the control
|
||||
inputs and their scaling, in the form:
|
||||
|
||||
S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
|
||||
|
||||
The <group> value identifies the control group from which the scaler will read,
|
||||
and the <index> value an offset within that group. These values are specific to
|
||||
the device reading the mixer definition.
|
||||
|
||||
When used to mix vehicle controls, mixer group zero is the vehicle attitude
|
||||
control group, and index values zero through three are normally roll, pitch,
|
||||
yaw and thrust respectively.
|
||||
|
||||
The remaining fields on the line configure the control scaler with parameters as
|
||||
discussed above. Whilst the calculations are performed as floating-point
|
||||
operations, the values stored in the definition file are scaled by a factor of
|
||||
10000; i.e. an offset of -0.5 is encoded as -5000.
|
||||
|
||||
Multirotor Mixer
|
||||
................
|
||||
|
||||
The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
|
||||
into a set of actuator outputs intended to drive motor speed controllers.
|
||||
|
||||
The mixer definition is a single line of the form:
|
||||
|
||||
R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
|
||||
|
||||
The supported geometries include:
|
||||
|
||||
4x - quadrotor in X configuration
|
||||
4+ - quadrotor in + configuration
|
||||
6x - hexcopter in X configuration
|
||||
6+ - hexcopter in + configuration
|
||||
8x - octocopter in X configuration
|
||||
8+ - octocopter in + configuration
|
||||
|
||||
Each of the roll, pitch and yaw scale values determine scaling of the roll,
|
||||
pitch and yaw controls relative to the thrust control. Whilst the calculations
|
||||
are performed as floating-point operations, the values stored in the definition
|
||||
file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
|
||||
|
||||
Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
|
||||
thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
|
||||
range -1.0 to 1.0.
|
||||
|
||||
In the case where an actuator saturates, all actuator values are rescaled so that
|
||||
the saturating actuator is limited to 1.0.
|
|
@ -0,0 +1,3 @@
|
|||
# Hexa coaxial
|
||||
|
||||
R: 6c 10000 10000 10000 0
|
|
@ -1,88 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# PX4FMU startup script for logging purposes
|
||||
#
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
# Play SOS
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Start sensor drivers here.
|
||||
#
|
||||
|
||||
ms5611 start
|
||||
adc start
|
||||
|
||||
# mag might be external
|
||||
if hmc5883 start
|
||||
then
|
||||
echo "using HMC5883"
|
||||
fi
|
||||
|
||||
if mpu6000 start
|
||||
then
|
||||
echo "using MPU6000"
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
echo "using L3GD20(H)"
|
||||
fi
|
||||
|
||||
if lsm303d start
|
||||
then
|
||||
set BOARD fmuv2
|
||||
else
|
||||
set BOARD fmuv1
|
||||
fi
|
||||
|
||||
# Start airspeed sensors
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "using MEAS airspeed sensor"
|
||||
else
|
||||
if ets_airspeed start
|
||||
then
|
||||
echo "using ETS airspeed sensor (bus 3)"
|
||||
else
|
||||
if ets_airspeed start -b 1
|
||||
then
|
||||
echo "Using ETS airspeed sensor (bus 1)"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensor collection task.
|
||||
# IMPORTANT: this also loads param offsets
|
||||
# ALWAYS start this task before the
|
||||
# preflight_check.
|
||||
#
|
||||
if sensors start
|
||||
then
|
||||
echo "SENSORS STARTED"
|
||||
fi
|
||||
|
||||
sdlog2 start -r 250 -e -b 16
|
||||
|
||||
if sercon
|
||||
then
|
||||
echo "[init] USB interface connected"
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
Binary file not shown.
|
@ -2,6 +2,7 @@
|
|||
#
|
||||
# PX4FMU startup script for test hackery.
|
||||
#
|
||||
uorb start
|
||||
|
||||
if sercon
|
||||
then
|
||||
|
@ -9,4 +10,68 @@ then
|
|||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
# Play SOS
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
#
|
||||
# Start a minimal system
|
||||
#
|
||||
|
||||
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"
|
||||
fi
|
||||
|
||||
if px4io checkcrc $io_file
|
||||
then
|
||||
echo "PX4IO CRC OK"
|
||||
else
|
||||
echo "PX4IO CRC failure"
|
||||
tone_alarm MBABGP
|
||||
if px4io forceupdate 14662 $io_file
|
||||
then
|
||||
usleep 500000
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO restart OK"
|
||||
tone_alarm MSPAA
|
||||
else
|
||||
echo "PX4IO restart failed"
|
||||
tone_alarm MNGGG
|
||||
sleep 5
|
||||
reboot
|
||||
fi
|
||||
else
|
||||
echo "PX4IO update failed"
|
||||
tone_alarm MNGGG
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# The presence of this file suggests we're running a mount stress test
|
||||
#
|
||||
if [ -f /fs/microsd/mount_test_cmds.txt ]
|
||||
then
|
||||
tests mount
|
||||
fi
|
||||
|
|
|
@ -16,4 +16,5 @@ astyle \
|
|||
--ignore-exclude-errors-x \
|
||||
--lineend=linux \
|
||||
--exclude=EASTL \
|
||||
--add-brackets \
|
||||
$*
|
||||
|
|
|
@ -1,19 +0,0 @@
|
|||
#!/bin/sh
|
||||
astyle \
|
||||
--style=linux \
|
||||
--indent=force-tab=8 \
|
||||
--indent-cases \
|
||||
--indent-preprocessor \
|
||||
--break-blocks=all \
|
||||
--pad-oper \
|
||||
--pad-header \
|
||||
--unpad-paren \
|
||||
--keep-one-line-blocks \
|
||||
--keep-one-line-statements \
|
||||
--align-pointer=name \
|
||||
--suffix=none \
|
||||
--lineend=linux \
|
||||
$*
|
||||
#--ignore-exclude-errors-x \
|
||||
#--exclude=EASTL \
|
||||
#--align-reference=name \
|
|
@ -0,0 +1,201 @@
|
|||
#!/usr/bin/env python3
|
||||
|
||||
"""fsm_visualisation.py: Create dot code and dokuwiki table from a state transition table
|
||||
|
||||
convert dot code to png using graphviz:
|
||||
|
||||
dot fsm.dot -Tpng -o fsm.png
|
||||
"""
|
||||
|
||||
import argparse
|
||||
import re
|
||||
|
||||
__author__ = "Julian Oes"
|
||||
|
||||
def get_dot_header():
|
||||
|
||||
return """digraph finite_state_machine {
|
||||
graph [ dpi = 300 ];
|
||||
ratio = 1.5
|
||||
node [shape = circle];"""
|
||||
|
||||
def get_dot_footer():
|
||||
|
||||
return """}\n"""
|
||||
|
||||
def main():
|
||||
|
||||
# parse input arguments
|
||||
parser = argparse.ArgumentParser(description='Create dot code and dokuwiki table from a state transition table.')
|
||||
parser.add_argument("-i", "--input-file", default=None, help="choose file to parse")
|
||||
parser.add_argument("-d", "--dot-file", default=None, help="choose file for output dot file")
|
||||
parser.add_argument("-t", "--table-file", default=None, help="choose file for output of table")
|
||||
args = parser.parse_args()
|
||||
|
||||
# open source file
|
||||
if args.input_file == None:
|
||||
exit('please specify file')
|
||||
f = open(args.input_file,'r')
|
||||
source = f.read()
|
||||
|
||||
# search for state transition table and extract the table itself
|
||||
# first look for StateTable::Tran
|
||||
# then accept anything including newline until {
|
||||
# but don't accept the definition (without ;)
|
||||
# then extract anything inside the brackets until };
|
||||
match = re.search(r'StateTable::Tran(?:.|\n!;)*\{((?:.|\n)*?)\};', source)
|
||||
|
||||
if not match:
|
||||
exit('no state transition table found')
|
||||
|
||||
table_source = match.group(1)
|
||||
|
||||
# bookkeeping for error checking
|
||||
num_errors_found = 0
|
||||
|
||||
states = []
|
||||
events = []
|
||||
|
||||
# first get all states and events
|
||||
for table_line in table_source.split('\n'):
|
||||
|
||||
match = re.search(r'/\*\s+\w+_STATE_(\w+)\s+\*/', table_line)
|
||||
if match:
|
||||
states.append(str(match.group(1)))
|
||||
# go to next line
|
||||
continue
|
||||
|
||||
if len(states) == 1:
|
||||
match = re.search(r'/\*\s+EVENT_(\w+)\s+\*/', table_line)
|
||||
if match:
|
||||
events.append(str(match.group(1)))
|
||||
|
||||
print('Found %d states and %d events' % (len(states), len(events)))
|
||||
|
||||
|
||||
# keep track of origin state
|
||||
state = None
|
||||
|
||||
# fill dot code in here
|
||||
dot_code = ''
|
||||
|
||||
# create table len(states)xlen(events)
|
||||
transition_table = [[[] for x in range(len(states))] for y in range(len(events))]
|
||||
|
||||
# now fill the transition table and write the dot code
|
||||
for table_line in table_source.split('\n'):
|
||||
|
||||
# get states
|
||||
# from: /* NAV_STATE_NONE */
|
||||
# extract only "NONE"
|
||||
match = re.search(r'/\*\s+\w+_STATE_(\w+)\s+\*/', table_line)
|
||||
if match:
|
||||
state = match.group(1)
|
||||
state_index = states.index(state)
|
||||
# go to next line
|
||||
continue
|
||||
|
||||
# can't advance without proper state
|
||||
if state == None:
|
||||
continue
|
||||
|
||||
# get event and next state
|
||||
# from /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY}
|
||||
# extract "READY_REQUESTED" and "READY" if there is ACTION
|
||||
match_action = re.search(r'/\*\s+EVENT_(\w+)\s+\*/\s+\{ACTION\((?:.|\n)*\w+_STATE_(\w+)', table_line)
|
||||
|
||||
# get event and next state
|
||||
# from /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE},
|
||||
# extract "NONE_REQUESTED" and "NAV_STATE_NONE" if there is NO_ACTION
|
||||
match_no_action = re.search(r'/\*\s+EVENT_(\w+)\s+\*/\s+\{NO_ACTION(?:.|\n)*\w+_STATE_(\w+)', table_line)
|
||||
|
||||
# ignore lines with brackets only
|
||||
if match_action or match_no_action:
|
||||
|
||||
# only write arrows for actions
|
||||
if match_action:
|
||||
event = match_action.group(1)
|
||||
new_state = match_action.group(2)
|
||||
dot_code += ' ' + state + ' -> ' + new_state + '[ label = "' + event + '"];\n'
|
||||
|
||||
elif match_no_action:
|
||||
event = match_no_action.group(1)
|
||||
new_state = match_no_action.group(2)
|
||||
|
||||
# check for state changes without action
|
||||
if state != new_state:
|
||||
print('Error: no action but state change:')
|
||||
print('State: ' + state + ' changed to: ' + new_state)
|
||||
print(table_line)
|
||||
num_errors_found += 1
|
||||
|
||||
# check for wrong events
|
||||
if event not in events:
|
||||
print('Error: unknown event: ' + event)
|
||||
print(table_line)
|
||||
num_errors_found += 1
|
||||
|
||||
# check for wrong new states
|
||||
if new_state not in states:
|
||||
print('Error: unknown new state: ' + new_state)
|
||||
print(table_line)
|
||||
num_errors_found += 1
|
||||
|
||||
# save new state in transition table
|
||||
event_index = events.index(event)
|
||||
|
||||
# bold for action
|
||||
if match_action:
|
||||
transition_table[event_index][state_index] = '**' + new_state + '**'
|
||||
else:
|
||||
transition_table[event_index][state_index] = new_state
|
||||
|
||||
|
||||
|
||||
# assemble dot code
|
||||
dot_code = get_dot_header() + dot_code + get_dot_footer()
|
||||
|
||||
# write or print dot file
|
||||
if args.dot_file:
|
||||
f = open(args.dot_file,'w')
|
||||
f.write(dot_code)
|
||||
print('Wrote dot file')
|
||||
else:
|
||||
print('##########Dot-start##########')
|
||||
print(dot_code)
|
||||
print('##########Dot-end############')
|
||||
|
||||
|
||||
# assemble doku wiki table
|
||||
table_code = '| ^ '
|
||||
# start with header of all states
|
||||
for state in states:
|
||||
table_code += state + ' ^ '
|
||||
|
||||
table_code += '\n'
|
||||
|
||||
# add events and new states
|
||||
for event, row in zip(events, transition_table):
|
||||
table_code += '^ ' + event + ' | '
|
||||
for new_state in row:
|
||||
table_code += new_state + ' | '
|
||||
table_code += '\n'
|
||||
|
||||
# write or print wiki table
|
||||
if args.table_file:
|
||||
f = open(args.table_file,'w')
|
||||
f.write(table_code)
|
||||
print('Wrote table file')
|
||||
else:
|
||||
print('##########Table-start########')
|
||||
print(table_code)
|
||||
print('##########Table-end##########')
|
||||
|
||||
# report obvous errors
|
||||
if num_errors_found:
|
||||
print('Obvious errors found: %d' % num_errors_found)
|
||||
else:
|
||||
print('No obvious errors found')
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
|
@ -1,2 +1,4 @@
|
|||
parameters.wiki
|
||||
parameters.xml
|
||||
parameters.xml
|
||||
parameters.wikirpc.xml
|
||||
cookies.txt
|
|
@ -1,5 +0,0 @@
|
|||
class Output(object):
|
||||
def Save(self, groups, fn):
|
||||
data = self.Generate(groups)
|
||||
with open(fn, 'w') as f:
|
||||
f.write(data)
|
|
@ -1,7 +1,7 @@
|
|||
import output
|
||||
import codecs
|
||||
|
||||
class DokuWikiOutput(output.Output):
|
||||
def Generate(self, groups):
|
||||
class DokuWikiListingsOutput():
|
||||
def __init__(self, groups):
|
||||
result = ""
|
||||
for group in groups:
|
||||
result += "==== %s ====\n\n" % group.GetName()
|
||||
|
@ -24,4 +24,8 @@ class DokuWikiOutput(output.Output):
|
|||
if def_val is not None:
|
||||
result += "* Default value: %s\n" % def_val
|
||||
result += "\n"
|
||||
return result
|
||||
self.output = result
|
||||
|
||||
def Save(self, filename):
|
||||
with codecs.open(filename, 'w', 'utf-8') as f:
|
||||
f.write(self.output)
|
|
@ -0,0 +1,76 @@
|
|||
from xml.sax.saxutils import escape
|
||||
import codecs
|
||||
|
||||
class DokuWikiTablesOutput():
|
||||
def __init__(self, groups):
|
||||
result = "====== Parameter Reference ======\nThis list is auto-generated every few minutes and contains the most recent parameter names and default values.\n\n"
|
||||
for group in groups:
|
||||
result += "==== %s ====\n\n" % group.GetName()
|
||||
result += "|< 100% 20% 20% 10% 10% 10% 30%>|\n"
|
||||
result += "^ Name ^ Description ^ Min ^ Max ^ Default ^ Comment ^\n"
|
||||
for param in group.GetParams():
|
||||
code = param.GetFieldValue("code")
|
||||
name = param.GetFieldValue("short_desc")
|
||||
min_val = param.GetFieldValue("min")
|
||||
max_val = param.GetFieldValue("max")
|
||||
def_val = param.GetFieldValue("default")
|
||||
long_desc = param.GetFieldValue("long_desc")
|
||||
|
||||
name = name.replace("\n", " ")
|
||||
result += "| %s | %s |" % (code, name)
|
||||
|
||||
if min_val is not None:
|
||||
result += " %s |" % min_val
|
||||
else:
|
||||
result += " |"
|
||||
|
||||
if max_val is not None:
|
||||
result += " %s |" % max_val
|
||||
else:
|
||||
result += " |"
|
||||
|
||||
if def_val is not None:
|
||||
result += " %s |" % def_val
|
||||
else:
|
||||
result += " |"
|
||||
|
||||
if long_desc is not None:
|
||||
long_desc = long_desc.replace("\n", " ")
|
||||
result += " %s |" % long_desc
|
||||
else:
|
||||
result += " |"
|
||||
|
||||
result += "\n"
|
||||
result += "\n"
|
||||
self.output = result;
|
||||
|
||||
def Save(self, filename):
|
||||
with codecs.open(filename, 'w', 'utf-8') as f:
|
||||
f.write(self.output)
|
||||
|
||||
def SaveRpc(self, filename):
|
||||
with codecs.open(filename, 'w', 'utf-8') as f:
|
||||
f.write("""<?xml version='1.0'?>
|
||||
<methodCall>
|
||||
<methodName>wiki.putPage</methodName>
|
||||
<params>
|
||||
<param>
|
||||
<value>
|
||||
<string>:firmware:parameters</string>
|
||||
</value>
|
||||
</param>
|
||||
<param>
|
||||
<value>
|
||||
<string>""")
|
||||
f.write(escape(self.output))
|
||||
f.write("""</string>
|
||||
</value>
|
||||
</param>
|
||||
<param>
|
||||
<value>
|
||||
<name>sum</name>
|
||||
<string>Updated parameters automagically from code.</string>
|
||||
</value>
|
||||
</param>
|
||||
</params>
|
||||
</methodCall>""")
|
|
@ -1,8 +1,8 @@
|
|||
import output
|
||||
from xml.dom.minidom import getDOMImplementation
|
||||
import codecs
|
||||
|
||||
class XMLOutput(output.Output):
|
||||
def Generate(self, groups):
|
||||
class XMLOutput():
|
||||
def __init__(self, groups):
|
||||
impl = getDOMImplementation()
|
||||
xml_document = impl.createDocument(None, "parameters", None)
|
||||
xml_parameters = xml_document.documentElement
|
||||
|
@ -19,4 +19,8 @@ class XMLOutput(output.Output):
|
|||
xml_param.appendChild(xml_field)
|
||||
xml_value = xml_document.createTextNode(value)
|
||||
xml_field.appendChild(xml_value)
|
||||
return xml_document.toprettyxml(indent=" ", newl="\n", encoding="utf-8")
|
||||
self.xml_document = xml_document
|
||||
|
||||
def Save(self, filename):
|
||||
with codecs.open(filename, 'w', 'utf-8') as f:
|
||||
self.xml_document.writexml(f, indent=" ", addindent=" ", newl="\n")
|
|
@ -40,22 +40,28 @@
|
|||
#
|
||||
|
||||
import scanner
|
||||
import parser
|
||||
import xmlout
|
||||
import dokuwikiout
|
||||
import srcparser
|
||||
import output_xml
|
||||
import output_dokuwiki_tables
|
||||
import output_dokuwiki_listings
|
||||
|
||||
# Initialize parser
|
||||
prs = parser.Parser()
|
||||
prs = srcparser.Parser()
|
||||
|
||||
# Scan directories, and parse the files
|
||||
sc = scanner.Scanner()
|
||||
sc.ScanDir("../../src", prs)
|
||||
output = prs.GetParamGroups()
|
||||
groups = prs.GetParamGroups()
|
||||
|
||||
# Output into XML
|
||||
out = xmlout.XMLOutput()
|
||||
out.Save(output, "parameters.xml")
|
||||
out = output_xml.XMLOutput(groups)
|
||||
out.Save("parameters.xml")
|
||||
|
||||
# Output into DokuWiki
|
||||
out = dokuwikiout.DokuWikiOutput()
|
||||
out.Save(output, "parameters.wiki")
|
||||
# Output to DokuWiki listings
|
||||
#out = output_dokuwiki_listings.DokuWikiListingsOutput(groups)
|
||||
#out.Save("parameters.wiki")
|
||||
|
||||
# Output to DokuWiki tables
|
||||
out = output_dokuwiki_tables.DokuWikiTablesOutput(groups)
|
||||
out.Save("parameters.wiki")
|
||||
out.SaveRpc("parameters.wikirpc.xml")
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
import os
|
||||
import re
|
||||
import codecs
|
||||
|
||||
class Scanner(object):
|
||||
"""
|
||||
|
@ -29,6 +30,6 @@ class Scanner(object):
|
|||
Scans provided file and passes its contents to the parser using
|
||||
parser.Parse method.
|
||||
"""
|
||||
with open(path, 'r') as f:
|
||||
with codecs.open(path, 'r', 'utf-8') as f:
|
||||
contents = f.read()
|
||||
parser.Parse(contents)
|
||||
|
|
|
@ -28,8 +28,7 @@ class ParameterGroup(object):
|
|||
state of the parser.
|
||||
"""
|
||||
return sorted(self.params,
|
||||
cmp=lambda x, y: cmp(x.GetFieldValue("code"),
|
||||
y.GetFieldValue("code")))
|
||||
key=lambda x: x.GetFieldValue("code"))
|
||||
|
||||
class Parameter(object):
|
||||
"""
|
||||
|
@ -61,9 +60,10 @@ class Parameter(object):
|
|||
"""
|
||||
Return list of existing field codes in convenient order
|
||||
"""
|
||||
return sorted(self.fields.keys(),
|
||||
cmp=lambda x, y: cmp(self.priority.get(y, 0),
|
||||
self.priority.get(x, 0)) or cmp(x, y))
|
||||
keys = self.fields.keys()
|
||||
keys = sorted(keys)
|
||||
keys = sorted(keys, key=lambda x: self.priority.get(x, 0), reverse=True)
|
||||
return keys
|
||||
|
||||
def GetFieldValue(self, code):
|
||||
"""
|
||||
|
@ -197,7 +197,7 @@ class Parser(object):
|
|||
if tag == "group":
|
||||
group = tags[tag]
|
||||
elif tag not in self.valid_tags:
|
||||
sys.stderr.write("Skipping invalid"
|
||||
sys.stderr.write("Skipping invalid "
|
||||
"documentation tag: '%s'\n" % tag)
|
||||
else:
|
||||
param.SetField(tag, tags[tag])
|
||||
|
@ -214,7 +214,7 @@ class Parser(object):
|
|||
object. Note that returned object is not a copy. Modifications affect
|
||||
state of the parser.
|
||||
"""
|
||||
return sorted(self.param_groups.values(),
|
||||
cmp=lambda x, y: cmp(self.priority.get(y.GetName(), 0),
|
||||
self.priority.get(x.GetName(), 0)) or cmp(x.GetName(),
|
||||
y.GetName()))
|
||||
groups = self.param_groups.values()
|
||||
groups = sorted(groups, key=lambda x: x.GetName())
|
||||
groups = sorted(groups, key=lambda x: self.priority.get(x.GetName(), 0), reverse=True)
|
||||
return groups
|
|
@ -0,0 +1,5 @@
|
|||
python px_process_params.py
|
||||
|
||||
rm cookies.txt
|
||||
curl --cookie cookies.txt --cookie-jar cookies.txt --user-agent Mozilla/4.0 --data "u=$XMLRPCUSER&p=$XMLRPCPASS" https://pixhawk.org/start?do=login
|
||||
curl -k --cookie cookies.txt -H "Content-Type: application/xml" -X POST --data-binary @parameters.wikirpc.xml "https://pixhawk.org/lib/exe/xmlrpc.php"
|
|
@ -50,6 +50,9 @@
|
|||
# Currently only used for informational purposes.
|
||||
#
|
||||
|
||||
# for python2.7 compatibility
|
||||
from __future__ import print_function
|
||||
|
||||
import sys
|
||||
import argparse
|
||||
import binascii
|
||||
|
@ -154,6 +157,8 @@ class uploader(object):
|
|||
PROG_MULTI = b'\x27'
|
||||
READ_MULTI = b'\x28' # rev2 only
|
||||
GET_CRC = b'\x29' # rev3+
|
||||
GET_OTP = b'\x2a' # rev4+ , get a word from OTP area
|
||||
GET_SN = b'\x2b' # rev4+ , get a word from SN area
|
||||
REBOOT = b'\x30'
|
||||
|
||||
INFO_BL_REV = b'\x01' # bootloader protocol revision
|
||||
|
@ -175,6 +180,8 @@ class uploader(object):
|
|||
def __init__(self, portname, baudrate):
|
||||
# open the port, keep the default timeout short so we can poll quickly
|
||||
self.port = serial.Serial(portname, baudrate, timeout=0.5)
|
||||
self.otp = b''
|
||||
self.sn = b''
|
||||
|
||||
def close(self):
|
||||
if self.port is not None:
|
||||
|
@ -237,6 +244,22 @@ class uploader(object):
|
|||
self.__getSync()
|
||||
return value
|
||||
|
||||
# send the GET_OTP command and wait for an info parameter
|
||||
def __getOTP(self, param):
|
||||
t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array.
|
||||
self.__send(uploader.GET_OTP + t + uploader.EOC)
|
||||
value = self.__recv(4)
|
||||
self.__getSync()
|
||||
return value
|
||||
|
||||
# send the GET_OTP command and wait for an info parameter
|
||||
def __getSN(self, param):
|
||||
t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array.
|
||||
self.__send(uploader.GET_SN + t + uploader.EOC)
|
||||
value = self.__recv(4)
|
||||
self.__getSync()
|
||||
return value
|
||||
|
||||
# send the CHIP_ERASE command and wait for the bootloader to become ready
|
||||
def __erase(self):
|
||||
self.__send(uploader.CHIP_ERASE
|
||||
|
@ -353,6 +376,31 @@ class uploader(object):
|
|||
if self.fw_maxsize < fw.property('image_size'):
|
||||
raise RuntimeError("Firmware image is too large for this board")
|
||||
|
||||
# OTP added in v4:
|
||||
if self.bl_rev > 3:
|
||||
for byte in range(0,32*6,4):
|
||||
x = self.__getOTP(byte)
|
||||
self.otp = self.otp + x
|
||||
print(binascii.hexlify(x).decode('Latin-1') + ' ', end='')
|
||||
# see src/modules/systemlib/otp.h in px4 code:
|
||||
self.otp_id = self.otp[0:4]
|
||||
self.otp_idtype = self.otp[4:5]
|
||||
self.otp_vid = self.otp[8:4:-1]
|
||||
self.otp_pid = self.otp[12:8:-1]
|
||||
self.otp_coa = self.otp[32:160]
|
||||
# show user:
|
||||
print("type: " + self.otp_id.decode('Latin-1'))
|
||||
print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
|
||||
print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
|
||||
print("pid: "+ binascii.hexlify(self.otp_pid).decode('Latin-1'))
|
||||
print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
|
||||
print("sn: ", end='')
|
||||
for byte in range(0,12,4):
|
||||
x = self.__getSN(byte)
|
||||
x = x[::-1] # reverse the bytes
|
||||
self.sn = self.sn + x
|
||||
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
|
||||
print('')
|
||||
print("erase...")
|
||||
self.__erase()
|
||||
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -10,11 +10,13 @@ LIBS=-lm
|
|||
#_DEPS = test.h
|
||||
#DEPS = $(patsubst %,$(IDIR)/%,$(_DEPS))
|
||||
|
||||
_OBJ = mixer_test.o test_mixer.o mixer_simple.o mixer_multirotor.o mixer.o mixer_group.o mixer_load.o
|
||||
_OBJ = mixer_test.o test_mixer.o mixer_simple.o mixer_multirotor.o \
|
||||
mixer.o mixer_group.o mixer_load.o test_conv.o pwm_limit.o hrt.o
|
||||
OBJ = $(patsubst %,$(ODIR)/%,$(_OBJ))
|
||||
|
||||
#$(DEPS)
|
||||
$(ODIR)/%.o: %.cpp
|
||||
mkdir -p obj
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
$(ODIR)/%.o: ../../src/systemcmds/tests/%.cpp
|
||||
|
@ -26,6 +28,12 @@ $(ODIR)/%.o: ../../src/modules/systemlib/%.cpp
|
|||
$(ODIR)/%.o: ../../src/modules/systemlib/mixer/%.cpp
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
$(ODIR)/%.o: ../../src/modules/systemlib/pwm_limit/%.cpp
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
$(ODIR)/%.o: ../../src/modules/systemlib/pwm_limit/%.c
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
$(ODIR)/%.o: ../../src/modules/systemlib/mixer/%.c
|
||||
$(CC) -c -o $@ $< $(CFLAGS)
|
||||
|
||||
|
|
|
@ -0,0 +1,16 @@
|
|||
#include <sys/time.h>
|
||||
#include <inttypes.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <stdio.h>
|
||||
|
||||
hrt_abstime hrt_absolute_time() {
|
||||
struct timeval te;
|
||||
gettimeofday(&te, NULL); // get current time
|
||||
hrt_abstime us = static_cast<uint64_t>(te.tv_sec) * 1e6 + te.tv_usec; // caculate us
|
||||
return us;
|
||||
}
|
||||
|
||||
hrt_abstime hrt_elapsed_time(const volatile hrt_abstime *then) {
|
||||
// not thread safe
|
||||
return hrt_absolute_time() - *then;
|
||||
}
|
|
@ -9,4 +9,6 @@ int main(int argc, char *argv[]) {
|
|||
"../../ROMFS/px4fmu_common/mixers/FMU_quad_w.mix"};
|
||||
|
||||
test_mixer(3, args);
|
||||
|
||||
test_conv(1, args);
|
||||
}
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue