aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_common/init.d')
-rw-r--r--ROMFS/px4fmu_common/init.d/10_dji_f33014
-rw-r--r--ROMFS/px4fmu_common/init.d/11_dji_f45015
-rw-r--r--ROMFS/px4fmu_common/init.d/15_tbs_discovery15
-rw-r--r--ROMFS/px4fmu_common/init.d/16_3dr_iris15
-rw-r--r--ROMFS/px4fmu_common/init.d/666_fmu_q_x5502
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl10
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.custom_io_esc30
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.multirotor5
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS14
9 files changed, 68 insertions, 52 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10_dji_f330 b/ROMFS/px4fmu_common/init.d/10_dji_f330
index b8fe5fc31..81ea292aa 100644
--- a/ROMFS/px4fmu_common/init.d/10_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/10_dji_f330
@@ -59,11 +59,10 @@ then
mavlink start
usleep 5000
+ commander start
+
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 +80,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
diff --git a/ROMFS/px4fmu_common/init.d/11_dji_f450 b/ROMFS/px4fmu_common/init.d/11_dji_f450
index 388f40a47..4dbf76cee 100644
--- a/ROMFS/px4fmu_common/init.d/11_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/11_dji_f450
@@ -43,11 +43,9 @@ then
mavlink start
usleep 5000
+ commander start
+
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 +63,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
diff --git a/ROMFS/px4fmu_common/init.d/15_tbs_discovery b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
index cbfde6d3c..bd6189a6d 100644
--- a/ROMFS/px4fmu_common/init.d/15_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
@@ -43,11 +43,9 @@ then
mavlink start
usleep 5000
+ commander start
+
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 +63,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
diff --git a/ROMFS/px4fmu_common/init.d/16_3dr_iris b/ROMFS/px4fmu_common/init.d/16_3dr_iris
index 3ac086b91..d8cc0e913 100644
--- a/ROMFS/px4fmu_common/init.d/16_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/16_3dr_iris
@@ -43,11 +43,9 @@ then
mavlink start
usleep 5000
+ commander start
+
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 +63,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
diff --git a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550 b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
index ae41f2a01..eae37098b 100644
--- a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
+++ b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
@@ -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
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
index 51bc61c9e..a63d0e5f1 100644
--- a/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
+++ b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
@@ -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
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_io_esc b/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
index 2bfaed76c..0c0cfa53d 100644
--- a/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
+++ b/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
@@ -61,20 +61,9 @@ then
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
- sh /etc/init.d/rc.io
+ commander start
- if [ $ESC_MAKER = afro ]
- then
- # Set PWM values for Afro ESCs
- px4io idle 1050 1050 1050 1050
- px4io min 1080 1080 1080 1080
- px4io max 1860 1860 1860 1860
- else
- # Set PWM values for typical ESCs
- px4io idle 900 900 900 900
- px4io min 1110 1100 1100 1100
- px4io max 1800 1800 1800 1800
- fi
+ sh /etc/init.d/rc.io
else
fmu mode_pwm
# Start MAVLink (on UART1 / ttyS0)
@@ -84,6 +73,19 @@ else
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
#
@@ -105,7 +107,7 @@ fi
#
# Set PWM output frequency
#
-pwm -u 400 -m 0xff
+pwm rate -r 400 -c 1234
#
# Start common for all multirotors apps
diff --git a/ROMFS/px4fmu_common/init.d/rc.multirotor b/ROMFS/px4fmu_common/init.d/rc.multirotor
index e3638e3d1..dfff07198 100644
--- a/ROMFS/px4fmu_common/init.d/rc.multirotor
+++ b/ROMFS/px4fmu_common/init.d/rc.multirotor
@@ -14,11 +14,6 @@ sh /etc/init.d/rc.sensors
sh /etc/init.d/rc.logging
#
-# Start the commander.
-#
-commander start
-
-#
# Start GPS interface (depends on orb)
#
gps start
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 9d0800eb1..cff8446a6 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -265,13 +265,13 @@ then
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
+ # 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