mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 11:06:04 +08:00
rc scripts cleanup, avoid duplicating parameters, use inheritance instead
This commit is contained in:
@@ -10,13 +10,15 @@ then
|
|||||||
#
|
#
|
||||||
# Default parameters for this platform
|
# Default parameters for this platform
|
||||||
#
|
#
|
||||||
param set MC_ATT_P 5.0
|
param set MC_ROLL_P 5.0
|
||||||
param set MC_ATT_I 0.0
|
param set MC_ROLLRATE_P 0.17
|
||||||
|
param set MC_ROLLRATE_I 0.0
|
||||||
|
param set MC_ROLLRATE_D 0.006
|
||||||
|
param set MC_PITCH_P 5.0
|
||||||
|
param set MC_PITCHRATE_P 0.17
|
||||||
|
param set MC_PITCHRATE_I 0.0
|
||||||
|
param set MC_PITCHRATE_D 0.006
|
||||||
param set MC_YAW_P 0.5
|
param set MC_YAW_P 0.5
|
||||||
param set MC_YAW_I 0.15
|
|
||||||
param set MC_ATTRATE_P 0.17
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.006
|
|
||||||
param set MC_YAWRATE_P 0.2
|
param set MC_YAWRATE_P 0.2
|
||||||
param set MC_YAWRATE_I 0.0
|
param set MC_YAWRATE_I 0.0
|
||||||
param set MC_YAWRATE_D 0.0
|
param set MC_YAWRATE_D 0.0
|
||||||
|
|||||||
@@ -10,13 +10,15 @@ then
|
|||||||
#
|
#
|
||||||
# Default parameters for this platform
|
# Default parameters for this platform
|
||||||
#
|
#
|
||||||
param set MC_ATT_P 9.0
|
param set MC_ROLL_P 9.0
|
||||||
param set MC_ATT_I 0.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_YAW_P 0.5
|
||||||
param set MC_YAW_I 0.15
|
|
||||||
param set MC_ATTRATE_P 0.13
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWRATE_P 0.2
|
param set MC_YAWRATE_P 0.2
|
||||||
param set MC_YAWRATE_I 0.0
|
param set MC_YAWRATE_I 0.0
|
||||||
param set MC_YAWRATE_D 0.0
|
param set MC_YAWRATE_D 0.0
|
||||||
|
|||||||
@@ -5,38 +5,6 @@
|
|||||||
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
|
||||||
#
|
#
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
sh /etc/init.d/4001_quad_x
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ATT_P 7.0
|
|
||||||
param set MC_ATT_I 0.0
|
|
||||||
param set MC_YAW_P 2.0
|
|
||||||
param set MC_YAW_I 0.0
|
|
||||||
param set MC_ATTRATE_P 0.12
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWRATE_P 0.3
|
|
||||||
param set MC_YAWRATE_I 0.2
|
|
||||||
param set MC_YAWRATE_D 0.005
|
|
||||||
|
|
||||||
param set MPC_TILT_MAX 1.0
|
|
||||||
param set MPC_THR_MAX 1.0
|
|
||||||
param set MPC_THR_MIN 0.1
|
|
||||||
param set MPC_XY_P 1.0
|
|
||||||
param set MPC_XY_VEL_D 0.01
|
|
||||||
param set MPC_XY_VEL_I 0.02
|
|
||||||
param set MPC_XY_VEL_MAX 5
|
|
||||||
param set MPC_XY_VEL_P 0.1
|
|
||||||
param set MPC_Z_P 1.0
|
|
||||||
param set MPC_Z_VEL_D 0.0
|
|
||||||
param set MPC_Z_VEL_I 0.02
|
|
||||||
param set MPC_Z_VEL_MAX 3
|
|
||||||
param set MPC_Z_VEL_P 0.1
|
|
||||||
fi
|
|
||||||
|
|
||||||
set HIL yes
|
set HIL yes
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_quad_x
|
|
||||||
|
|||||||
+9
-9
@@ -10,15 +10,15 @@ then
|
|||||||
#
|
#
|
||||||
# Default parameters for this platform
|
# Default parameters for this platform
|
||||||
#
|
#
|
||||||
param set MC_ATT_P 7.0
|
param set MC_ROLL_P 7.0
|
||||||
param set MC_ATT_I 0.0
|
param set MC_ROLLRATE_P 0.12
|
||||||
param set MC_ATT_D 0.0
|
param set MC_ROLLRATE_I 0.0
|
||||||
param set MC_ATTRATE_P 0.12
|
param set MC_ROLLRATE_D 0.004
|
||||||
param set MC_ATTRATE_I 0.0
|
param set MC_PITCH_P 7.0
|
||||||
param set MC_ATTRATE_D 0.004
|
param set MC_PITCHRATE_P 0.12
|
||||||
param set MC_YAWPOS_P 2.0
|
param set MC_PITCHRATE_I 0.0
|
||||||
param set MC_YAWPOS_I 0.0
|
param set MC_PITCHRATE_D 0.004
|
||||||
param set MC_YAWPOS_D 0.0
|
param set MC_YAW_P 2.0
|
||||||
param set MC_YAWRATE_P 0.3
|
param set MC_YAWRATE_P 0.3
|
||||||
param set MC_YAWRATE_I 0.2
|
param set MC_YAWRATE_I 0.2
|
||||||
param set MC_YAWRATE_D 0.005
|
param set MC_YAWRATE_D 0.005
|
||||||
@@ -0,0 +1,52 @@
|
|||||||
|
#!nsh
|
||||||
|
#
|
||||||
|
# Generic 10” Quad X geometry
|
||||||
|
#
|
||||||
|
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
|
|
||||||
|
if [ $DO_AUTOCONFIG == yes ]
|
||||||
|
then
|
||||||
|
#
|
||||||
|
# Default parameters for this platform
|
||||||
|
#
|
||||||
|
param set MC_ROLL_P 7.0
|
||||||
|
param set MC_ROLLRATE_P 0.12
|
||||||
|
param set MC_ROLLRATE_I 0.0
|
||||||
|
param set MC_ROLLRATE_D 0.004
|
||||||
|
param set MC_PITCH_P 7.0
|
||||||
|
param set MC_PITCHRATE_P 0.12
|
||||||
|
param set MC_PITCHRATE_I 0.0
|
||||||
|
param set MC_PITCHRATE_D 0.004
|
||||||
|
param set MC_YAW_P 2.0
|
||||||
|
param set MC_YAWRATE_P 0.3
|
||||||
|
param set MC_YAWRATE_I 0.2
|
||||||
|
param set MC_YAWRATE_D 0.005
|
||||||
|
|
||||||
|
param set MPC_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 VEHICLE_TYPE mc
|
||||||
|
set MIXER FMU_quad_x
|
||||||
|
|
||||||
|
set PWM_OUTPUTS 1234
|
||||||
|
set PWM_RATE 400
|
||||||
|
set PWM_DISARMED 900
|
||||||
|
set PWM_MIN 1000
|
||||||
|
set PWM_MAX 2000
|
||||||
@@ -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,83 +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 attitude estimator
|
|
||||||
#
|
|
||||||
attitude_estimator_ekf start
|
|
||||||
|
|
||||||
#
|
|
||||||
# Start the position estimator
|
|
||||||
#
|
|
||||||
flow_position_estimator start
|
|
||||||
|
|
||||||
#
|
|
||||||
# Fire up the multi rotor attitude controller
|
|
||||||
#
|
|
||||||
mc_att_control_vector 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
|
|
||||||
@@ -10,13 +10,15 @@ then
|
|||||||
#
|
#
|
||||||
# Default parameters for this platform
|
# Default parameters for this platform
|
||||||
#
|
#
|
||||||
param set MC_ATT_P 7.0
|
param set MC_ROLL_P 7.0
|
||||||
param set MC_ATT_I 0.0
|
param set MC_ROLLRATE_P 0.12
|
||||||
|
param set MC_ROLLRATE_I 0.0
|
||||||
|
param set MC_ROLLRATE_D 0.004
|
||||||
|
param set MC_PITCH_P 7.0
|
||||||
|
param set MC_PITCHRATE_P 0.12
|
||||||
|
param set MC_PITCHRATE_I 0.0
|
||||||
|
param set MC_PITCHRATE_D 0.004
|
||||||
param set MC_YAW_P 2.8
|
param set MC_YAW_P 2.8
|
||||||
param set MC_YAW_I 0.0
|
|
||||||
param set MC_ATTRATE_P 0.12
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWRATE_P 0.2
|
param set MC_YAWRATE_P 0.2
|
||||||
param set MC_YAWRATE_I 0.05
|
param set MC_YAWRATE_I 0.05
|
||||||
param set MC_YAWRATE_D 0.0
|
param set MC_YAWRATE_D 0.0
|
||||||
|
|||||||
@@ -10,13 +10,15 @@ then
|
|||||||
#
|
#
|
||||||
# Default parameters for this platform
|
# Default parameters for this platform
|
||||||
#
|
#
|
||||||
param set MC_ATT_P 7.0
|
param set MC_ROLL_P 7.0
|
||||||
param set MC_ATT_I 0.0
|
param set MC_ROLLRATE_P 0.12
|
||||||
|
param set MC_ROLLRATE_I 0.0
|
||||||
|
param set MC_ROLLRATE_D 0.004
|
||||||
|
param set MC_PITCH_P 7.0
|
||||||
|
param set MC_PITCHRATE_P 0.12
|
||||||
|
param set MC_PITCHRATE_I 0.0
|
||||||
|
param set MC_PITCHRATE_D 0.004
|
||||||
param set MC_YAW_P 2.0
|
param set MC_YAW_P 2.0
|
||||||
param set MC_YAW_I 0.0
|
|
||||||
param set MC_ATTRATE_P 0.12
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWRATE_P 0.3
|
param set MC_YAWRATE_P 0.3
|
||||||
param set MC_YAWRATE_I 0.2
|
param set MC_YAWRATE_I 0.2
|
||||||
param set MC_YAWRATE_D 0.005
|
param set MC_YAWRATE_D 0.005
|
||||||
|
|||||||
@@ -10,13 +10,15 @@ then
|
|||||||
#
|
#
|
||||||
# Default parameters for this platform
|
# Default parameters for this platform
|
||||||
#
|
#
|
||||||
param set MC_ATT_P 5.5
|
param set MC_ROLL_P 5.5
|
||||||
param set MC_ATT_I 0
|
param set MC_ROLLRATE_P 0.14
|
||||||
|
param set MC_ROLLRATE_I 0
|
||||||
|
param set MC_ROLLRATE_D 0.006
|
||||||
|
param set MC_PITCH_P 5.5
|
||||||
|
param set MC_PITCHRATE_P 0.14
|
||||||
|
param set MC_PITCHRATE_I 0
|
||||||
|
param set MC_PITCHRATE_D 0.006
|
||||||
param set MC_YAW_P 0.6
|
param set MC_YAW_P 0.6
|
||||||
param set MC_YAW_I 0
|
|
||||||
param set MC_ATTRATE_P 0.14
|
|
||||||
param set MC_ATTRATE_I 0
|
|
||||||
param set MC_ATTRATE_D 0.006
|
|
||||||
param set MC_YAWRATE_P 0.08
|
param set MC_YAWRATE_P 0.08
|
||||||
param set MC_YAWRATE_I 0
|
param set MC_YAWRATE_I 0
|
||||||
param set MC_YAWRATE_D 0
|
param set MC_YAWRATE_D 0
|
||||||
|
|||||||
@@ -0,0 +1,10 @@
|
|||||||
|
#!nsh
|
||||||
|
#
|
||||||
|
# Generic 10” Quad + geometry
|
||||||
|
#
|
||||||
|
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
|
|
||||||
|
sh /etc/init.d/4001_quad_x
|
||||||
|
|
||||||
|
set MIXER FMU_quad_+
|
||||||
@@ -1,37 +0,0 @@
|
|||||||
#!nsh
|
|
||||||
#
|
|
||||||
# Generic 10” Quad + geometry
|
|
||||||
#
|
|
||||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
#
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ATT_P 7.0
|
|
||||||
param set MC_ATT_I 0.0
|
|
||||||
param set MC_ATT_D 0.0
|
|
||||||
param set MC_ATTRATE_P 0.12
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWPOS_P 2.0
|
|
||||||
param set MC_YAWPOS_I 0.0
|
|
||||||
param set MC_YAWPOS_D 0.0
|
|
||||||
param set MC_YAWRATE_P 0.3
|
|
||||||
param set MC_YAWRATE_I 0.2
|
|
||||||
param set MC_YAWRATE_D 0.005
|
|
||||||
|
|
||||||
# TODO add default MPC parameters
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_quad_+
|
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
|
||||||
set PWM_RATE 400
|
|
||||||
# DJI ESC range
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1200
|
|
||||||
set PWM_MAX 1900
|
|
||||||
@@ -0,0 +1,12 @@
|
|||||||
|
#!nsh
|
||||||
|
#
|
||||||
|
# Generic 10” Hexa X geometry
|
||||||
|
#
|
||||||
|
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
|
|
||||||
|
sh /etc/init.d/4001_quad_x
|
||||||
|
|
||||||
|
set MIXER FMU_hexa_x
|
||||||
|
|
||||||
|
set PWM_OUTPUTS 123456
|
||||||
@@ -1,37 +0,0 @@
|
|||||||
#!nsh
|
|
||||||
#
|
|
||||||
# Generic 10” Hexa X geometry
|
|
||||||
#
|
|
||||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
#
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ATT_P 7.0
|
|
||||||
param set MC_ATT_I 0.0
|
|
||||||
param set MC_ATT_D 0.0
|
|
||||||
param set MC_ATTRATE_P 0.12
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWPOS_P 2.0
|
|
||||||
param set MC_YAWPOS_I 0.0
|
|
||||||
param set MC_YAWPOS_D 0.0
|
|
||||||
param set MC_YAWRATE_P 0.3
|
|
||||||
param set MC_YAWRATE_I 0.2
|
|
||||||
param set MC_YAWRATE_D 0.005
|
|
||||||
|
|
||||||
# TODO add default MPC parameters
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_hexa_x
|
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
|
||||||
set PWM_RATE 400
|
|
||||||
# DJI ESC range
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1200
|
|
||||||
set PWM_MAX 1900
|
|
||||||
@@ -0,0 +1,10 @@
|
|||||||
|
#!nsh
|
||||||
|
#
|
||||||
|
# Generic 10” Hexa + geometry
|
||||||
|
#
|
||||||
|
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
|
|
||||||
|
sh /etc/init.d/6001_hexa_x
|
||||||
|
|
||||||
|
set MIXER FMU_hexa_+
|
||||||
@@ -1,37 +0,0 @@
|
|||||||
#!nsh
|
|
||||||
#
|
|
||||||
# Generic 10” Hexa + geometry
|
|
||||||
#
|
|
||||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
#
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ATT_P 7.0
|
|
||||||
param set MC_ATT_I 0.0
|
|
||||||
param set MC_ATT_D 0.0
|
|
||||||
param set MC_ATTRATE_P 0.12
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWPOS_P 2.0
|
|
||||||
param set MC_YAWPOS_I 0.0
|
|
||||||
param set MC_YAWPOS_D 0.0
|
|
||||||
param set MC_YAWRATE_P 0.3
|
|
||||||
param set MC_YAWRATE_I 0.2
|
|
||||||
param set MC_YAWRATE_D 0.005
|
|
||||||
|
|
||||||
# TODO add default MPC parameters
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_hexa_+
|
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
|
||||||
set PWM_RATE 400
|
|
||||||
# DJI ESC range
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1200
|
|
||||||
set PWM_MAX 1900
|
|
||||||
@@ -0,0 +1,12 @@
|
|||||||
|
#!nsh
|
||||||
|
#
|
||||||
|
# Generic 10” Octo X geometry
|
||||||
|
#
|
||||||
|
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
|
|
||||||
|
sh /etc/init.d/4001_quad_x
|
||||||
|
|
||||||
|
set MIXER FMU_octo_x
|
||||||
|
|
||||||
|
set PWM_OUTPUTS 12345678
|
||||||
@@ -1,37 +0,0 @@
|
|||||||
#!nsh
|
|
||||||
#
|
|
||||||
# Generic 10” Octo X geometry
|
|
||||||
#
|
|
||||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
#
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ATT_P 7.0
|
|
||||||
param set MC_ATT_I 0.0
|
|
||||||
param set MC_ATT_D 0.0
|
|
||||||
param set MC_ATTRATE_P 0.12
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWPOS_P 2.0
|
|
||||||
param set MC_YAWPOS_I 0.0
|
|
||||||
param set MC_YAWPOS_D 0.0
|
|
||||||
param set MC_YAWRATE_P 0.3
|
|
||||||
param set MC_YAWRATE_I 0.2
|
|
||||||
param set MC_YAWRATE_D 0.005
|
|
||||||
|
|
||||||
# TODO add default MPC parameters
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_octo_x
|
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
|
||||||
set PWM_RATE 400
|
|
||||||
# DJI ESC range
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1200
|
|
||||||
set PWM_MAX 1900
|
|
||||||
@@ -0,0 +1,10 @@
|
|||||||
|
#!nsh
|
||||||
|
#
|
||||||
|
# Generic 10” Octo + geometry
|
||||||
|
#
|
||||||
|
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
|
||||||
|
#
|
||||||
|
|
||||||
|
sh /etc/init.d/8001_octo_x
|
||||||
|
|
||||||
|
set MIXER FMU_octo_+
|
||||||
@@ -1,37 +0,0 @@
|
|||||||
#!nsh
|
|
||||||
#
|
|
||||||
# Generic 10” Octo + geometry
|
|
||||||
#
|
|
||||||
# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
#
|
|
||||||
|
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
|
||||||
then
|
|
||||||
#
|
|
||||||
# Default parameters for this platform
|
|
||||||
#
|
|
||||||
param set MC_ATT_P 7.0
|
|
||||||
param set MC_ATT_I 0.0
|
|
||||||
param set MC_ATT_D 0.0
|
|
||||||
param set MC_ATTRATE_P 0.12
|
|
||||||
param set MC_ATTRATE_I 0.0
|
|
||||||
param set MC_ATTRATE_D 0.004
|
|
||||||
param set MC_YAWPOS_P 2.0
|
|
||||||
param set MC_YAWPOS_I 0.0
|
|
||||||
param set MC_YAWPOS_D 0.0
|
|
||||||
param set MC_YAWRATE_P 0.3
|
|
||||||
param set MC_YAWRATE_I 0.2
|
|
||||||
param set MC_YAWRATE_D 0.005
|
|
||||||
|
|
||||||
# TODO add default MPC parameters
|
|
||||||
fi
|
|
||||||
|
|
||||||
set VEHICLE_TYPE mc
|
|
||||||
set MIXER FMU_octo_+
|
|
||||||
|
|
||||||
set PWM_OUTPUTS 1234
|
|
||||||
set PWM_RATE 400
|
|
||||||
# DJI ESC range
|
|
||||||
set PWM_DISARMED 900
|
|
||||||
set PWM_MIN 1200
|
|
||||||
set PWM_MAX 1900
|
|
||||||
@@ -101,14 +101,9 @@ fi
|
|||||||
# Quad X
|
# Quad X
|
||||||
#
|
#
|
||||||
|
|
||||||
if param compare SYS_AUTOSTART 4008 8
|
if param compare SYS_AUTOSTART 4001
|
||||||
then
|
then
|
||||||
#sh /etc/init.d/4008_ardrone
|
sh /etc/init.d/4001_quad_x
|
||||||
fi
|
|
||||||
|
|
||||||
if param compare SYS_AUTOSTART 4009 9
|
|
||||||
then
|
|
||||||
#sh /etc/init.d/4009_ardrone_flow
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if param compare SYS_AUTOSTART 4010 10
|
if param compare SYS_AUTOSTART 4010 10
|
||||||
@@ -132,7 +127,7 @@ fi
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 5001
|
if param compare SYS_AUTOSTART 5001
|
||||||
then
|
then
|
||||||
sh /etc/init.d/5001_quad_+_pwm
|
sh /etc/init.d/5001_quad_+
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -141,7 +136,7 @@ fi
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 6001
|
if param compare SYS_AUTOSTART 6001
|
||||||
then
|
then
|
||||||
sh /etc/init.d/6001_hexa_x_pwm
|
sh /etc/init.d/6001_hexa_x
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -150,7 +145,7 @@ fi
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 7001
|
if param compare SYS_AUTOSTART 7001
|
||||||
then
|
then
|
||||||
sh /etc/init.d/7001_hexa_+_pwm
|
sh /etc/init.d/7001_hexa_+
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -159,7 +154,7 @@ fi
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 8001
|
if param compare SYS_AUTOSTART 8001
|
||||||
then
|
then
|
||||||
sh /etc/init.d/8001_octo_x_pwm
|
sh /etc/init.d/8001_octo_x
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -168,7 +163,7 @@ fi
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 9001
|
if param compare SYS_AUTOSTART 9001
|
||||||
then
|
then
|
||||||
sh /etc/init.d/9001_octo_+_pwm
|
sh /etc/init.d/9001_octo_+
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -191,5 +186,5 @@ fi
|
|||||||
|
|
||||||
if param compare SYS_AUTOSTART 12001
|
if param compare SYS_AUTOSTART 12001
|
||||||
then
|
then
|
||||||
sh /etc/init.d/12001_octo_cox_pwm
|
sh /etc/init.d/12001_octo_cox
|
||||||
fi
|
fi
|
||||||
|
|||||||
Reference in New Issue
Block a user