forked from Archive/PX4-Autopilot
Adapt startup scripts to new pwm systemcmd interface
This commit is contained in:
parent
ea0aa49b54
commit
03edf90161
|
@ -61,9 +61,6 @@ then
|
|||
|
||||
sh /etc/init.d/rc.io
|
||||
# Set PWM values for DJI ESCs
|
||||
px4io idle 900 900 900 900
|
||||
px4io min 1200 1200 1200 1200
|
||||
px4io max 1800 1800 1800 1800
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
@ -81,7 +78,14 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
|||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm -u 400 -m 0xff
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1200
|
||||
pwm max -c 1234 -p 1800
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
|
|
|
@ -44,10 +44,6 @@ then
|
|||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Set PWM values for DJI ESCs
|
||||
px4io idle 900 900 900 900
|
||||
px4io min 1200 1200 1200 1200
|
||||
px4io max 1800 1800 1800 1800
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
@ -65,7 +61,14 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
|||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm -u 400 -m 0xff
|
||||
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
|
||||
|
|
|
@ -44,10 +44,6 @@ then
|
|||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Set PWM values for DJI ESCs
|
||||
px4io idle 900 900 900 900
|
||||
px4io min 1200 1200 1200 1200
|
||||
px4io max 1800 1800 1800 1800
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
@ -65,7 +61,14 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
|||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm -u 400 -m 0xff
|
||||
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
|
||||
|
|
|
@ -44,10 +44,6 @@ then
|
|||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Set PWM values for DJI ESCs
|
||||
px4io idle 900 900 900 900
|
||||
px4io min 1200 1200 1200 1200
|
||||
px4io max 1800 1800 1800 1800
|
||||
else
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
mavlink start -d /dev/ttyS0
|
||||
|
@ -65,7 +61,14 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
|
|||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm -u 400 -m 0xff
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1200
|
||||
pwm max -c 1234 -p 1800
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
|
|
|
@ -53,7 +53,7 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
|||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
pwm -u 400 -m 0xff
|
||||
pwm rate -c 1234 -r 400
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
|
|
|
@ -83,10 +83,6 @@ then
|
|||
usleep 5000
|
||||
|
||||
sh /etc/init.d/rc.io
|
||||
# Set PWM values for DJI ESCs
|
||||
px4io idle 900 900 900 900
|
||||
px4io min 1200 1200 1200 1200
|
||||
px4io max 1800 1800 1800 1800
|
||||
else
|
||||
fmu mode_pwm
|
||||
# Start MAVLink (on UART1 / ttyS0)
|
||||
|
@ -107,9 +103,11 @@ else
|
|||
fi
|
||||
|
||||
#
|
||||
# Set PWM output frequency
|
||||
# Set disarmed, min and max PWM signals
|
||||
#
|
||||
#pwm -u 400 -m 0xff
|
||||
pwm disarmed -c 1234 -p 900
|
||||
pwm min -c 1234 -p 1200
|
||||
pwm max -c 1234 -p 1800
|
||||
|
||||
#
|
||||
# Start common for all multirotors apps
|
||||
|
|
Loading…
Reference in New Issue