forked from Archive/PX4-Autopilot
Updated / added all system types that have been available before
This commit is contained in:
parent
ba90dc87f6
commit
068cc190e2
|
@ -1,14 +1,13 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HILStar / X-Plane
|
||||
#
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting.."
|
||||
echo "HIL Rascal 110 starting.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
|
@ -40,48 +39,7 @@ then
|
|||
param save
|
||||
fi
|
||||
|
||||
# Allow USB some time to come up
|
||||
sleep 1
|
||||
# Tell MAVLink that this link is "fast"
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
|
||||
# Create a fake HIL /dev/pwm_output interface
|
||||
hil mode_pwm
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Check if we got an IO
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
echo "IO started"
|
||||
else
|
||||
fmu mode_serial
|
||||
echo "FMU started"
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
att_pos_estimator_ekf start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
|
||||
fw_pos_control_l1 start
|
||||
fw_att_control start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
set HIL yes
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
||||
|
|
|
@ -1,14 +1,13 @@
|
|||
#!nsh
|
||||
#
|
||||
# USB HIL start
|
||||
# HIL Rascal 110 (Flightgear)
|
||||
#
|
||||
# Maintainers: Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
echo "[HIL] HILStar starting in state-HIL mode.."
|
||||
echo "HIL Rascal 110 starting.."
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
|
@ -32,48 +31,15 @@ then
|
|||
param set FW_T_SINK_MAX 5.0
|
||||
param set FW_T_SINK_MIN 4.0
|
||||
param set FW_Y_ROLLFF 1.1
|
||||
param set FW_L1_PERIOD 16
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
# Allow USB some time to come up
|
||||
sleep 1
|
||||
# Tell MAVLink that this link is "fast"
|
||||
mavlink start -b 230400 -d /dev/ttyACM0
|
||||
|
||||
# Create a fake HIL /dev/pwm_output interface
|
||||
hil mode_pwm
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Check if we got an IO
|
||||
#
|
||||
if px4io start
|
||||
then
|
||||
echo "IO started"
|
||||
else
|
||||
fmu mode_serial
|
||||
echo "FMU started"
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
|
||||
fw_pos_control_l1 start
|
||||
fw_att_control start
|
||||
|
||||
echo "[HIL] setup done, running"
|
||||
set HIL yes
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
||||
|
|
|
@ -43,4 +43,3 @@ set HIL yes
|
|||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
||||
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo coaxial 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_cox
|
||||
|
||||
set PWM_OUTPUTS 1234
|
||||
set PWM_RATE 400
|
||||
# DJI ESC range
|
||||
set PWM_DISARMED 900
|
||||
set PWM_MIN 1200
|
||||
set PWM_MAX 1900
|
|
@ -1,11 +1,11 @@
|
|||
#!nsh
|
||||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on HK Bixler"
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set FW_P_D 0
|
||||
|
@ -35,46 +35,6 @@ then
|
|||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_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
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
|
@ -5,7 +5,7 @@ echo "[init] PX4FMU v1, v2 with or without IO on 3DR SkyWalker"
|
|||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set FW_P_D 0
|
||||
|
@ -35,48 +35,6 @@ then
|
|||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
fi
|
||||
|
||||
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
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_AERT
|
|
@ -2,57 +2,39 @@
|
|||
|
||||
echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
# TODO
|
||||
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start and configure PX4IO or FMU interface
|
||||
#
|
||||
if px4io detect
|
||||
then
|
||||
# Start MAVLink (depends on orb)
|
||||
mavlink start
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||
px4io limit 100
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
||||
fmu mode_pwm
|
||||
param set BAT_V_SCALING 0.004593
|
||||
set EXIT_ON_END yes
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_AIRSPD_MIN 7
|
||||
param set FW_AIRSPD_TRIM 9
|
||||
param set FW_AIRSPD_MAX 14
|
||||
param set FW_L1_PERIOD 10
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 20
|
||||
param set FW_P_LIM_MAX 30
|
||||
param set FW_P_LIM_MIN -20
|
||||
param set FW_P_P 30
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 2
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 20
|
||||
param set FW_R_P 60
|
||||
param set FW_R_RMAX 60
|
||||
param set FW_THR_CRUISE 0.65
|
||||
param set FW_THR_MAX 0.7
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5
|
||||
param set FW_T_SINK_MIN 2
|
||||
param set FW_T_TIME_CONST 9
|
||||
param set FW_Y_ROLLFF 2.0
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
fi
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
|
||||
then
|
||||
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
|
||||
else
|
||||
echo "Using /etc/mixers/FMU_Q.mix"
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
fi
|
||||
|
||||
#
|
||||
# Start common fixedwing apps
|
||||
#
|
||||
sh /etc/init.d/rc.fixedwing
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_Q
|
||||
|
|
|
@ -7,8 +7,37 @@
|
|||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# TODO
|
||||
#
|
||||
# Default parameters for this platform
|
||||
#
|
||||
param set FW_AIRSPD_MIN 7
|
||||
param set FW_AIRSPD_TRIM 9
|
||||
param set FW_AIRSPD_MAX 14
|
||||
param set FW_L1_PERIOD 10
|
||||
param set FW_P_D 0
|
||||
param set FW_P_I 0
|
||||
param set FW_P_IMAX 20
|
||||
param set FW_P_LIM_MAX 30
|
||||
param set FW_P_LIM_MIN -20
|
||||
param set FW_P_P 30
|
||||
param set FW_P_RMAX_NEG 0
|
||||
param set FW_P_RMAX_POS 0
|
||||
param set FW_P_ROLLFF 2
|
||||
param set FW_R_D 0
|
||||
param set FW_R_I 5
|
||||
param set FW_R_IMAX 20
|
||||
param set FW_R_P 60
|
||||
param set FW_R_RMAX 60
|
||||
param set FW_THR_CRUISE 0.65
|
||||
param set FW_THR_MAX 0.7
|
||||
param set FW_THR_MIN 0
|
||||
param set FW_T_SINK_MAX 5
|
||||
param set FW_T_SINK_MIN 2
|
||||
param set FW_T_TIME_CONST 9
|
||||
param set FW_Y_ROLLFF 2.0
|
||||
param set RC_SCALE_ROLL 1.0
|
||||
param set RC_SCALE_PITCH 1.0
|
||||
fi
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
set MIXER FMU_Q
|
||||
set MIXER FMU_X5
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
#!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,37 @@
|
|||
#!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,37 @@
|
|||
#!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,37 @@
|
|||
#!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,37 @@
|
|||
#!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
|
Loading…
Reference in New Issue