aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/100_mpx_easystar
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/100_mpx_easystar')
-rw-r--r--ROMFS/px4fmu_common/init.d/100_mpx_easystar84
1 files changed, 62 insertions, 22 deletions
diff --git a/ROMFS/px4fmu_common/init.d/100_mpx_easystar b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
index e1cefdb99..4f843e9aa 100644
--- a/ROMFS/px4fmu_common/init.d/100_mpx_easystar
+++ b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
@@ -1,6 +1,6 @@
#!nsh
-echo "[init] Multiplex Easystar"
+echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
#
# Load default params for this platform
@@ -8,7 +8,29 @@ echo "[init] Multiplex Easystar"
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
- # TODO
+ 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
@@ -20,28 +42,34 @@ fi
#
param set MAV_TYPE 1
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
+set EXIT_ON_END no
#
-# Start and configure PX4IO interface
+# Start and configure PX4IO or FMU interface
#
-sh /etc/init.d/rc.io
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+
+ commander 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
+
+ commander start
+
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
#
-# Set actuator limit to 100 Hz update (50 Hz PWM)
-px4io limit 100
-
-#
-# Start the commander
-#
-commander start
-
-#
-# Start the sensors
+# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
@@ -49,9 +77,9 @@ sh /etc/init.d/rc.sensors
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
-
+
#
-# Start GPS interface
+# Start GPS interface (depends on orb)
#
gps start
@@ -63,6 +91,18 @@ att_pos_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
-mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
+if [ -f /fs/microsd/etc/mixers/FMU_RET.mix ]
+then
+ echo "Using FMU_RET mixer from sd card"
+ mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_RET.mix
+else
+ echo "Using standard FMU_RET mixer"
+ mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
+fi
fw_att_control start
fw_pos_control_l1 start
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi