aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/px4fmu_common/init.d/08_ardrone1
-rw-r--r--ROMFS/px4fmu_common/init.d/09_ardrone_flow1
-rw-r--r--ROMFS/px4fmu_common/init.d/1001_rc_quad.hil110
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl122
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS52
5 files changed, 283 insertions, 3 deletions
diff --git a/ROMFS/px4fmu_common/init.d/08_ardrone b/ROMFS/px4fmu_common/init.d/08_ardrone
index 7dbbb8284..f6f09ac22 100644
--- a/ROMFS/px4fmu_common/init.d/08_ardrone
+++ b/ROMFS/px4fmu_common/init.d/08_ardrone
@@ -30,6 +30,7 @@ fi
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
+param set BAT_V_SCALING 0.008381
#
# Start MAVLink
diff --git a/ROMFS/px4fmu_common/init.d/09_ardrone_flow b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
index 6333aae56..9b739f245 100644
--- a/ROMFS/px4fmu_common/init.d/09_ardrone_flow
+++ b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
@@ -30,6 +30,7 @@ fi
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
+param set BAT_V_SCALING 0.008381
#
# Start MAVLink and MAVLink Onboard (PX4FLOW Sensor)
diff --git a/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
new file mode 100644
index 000000000..bbe3b7e28
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
@@ -0,0 +1,110 @@
+#!nsh
+#
+# USB HIL start
+#
+
+echo "[HIL] HILS quadrotor starting.."
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.0
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.05
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 3.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.1
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.05
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.5
+ param set MPC_THR_MIN 0.1
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ 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 2
+
+#
+# Start the commander (depends on orb, mavlink)
+#
+commander start
+
+#
+# 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_quad_x.mix
+
+#
+# Start position estimator
+#
+position_estimator_inav start
+
+#
+# Start attitude control
+#
+multirotor_att_control start
+
+#
+# Start position control
+#
+multirotor_pos_control start
+
+echo "[HIL] setup done, running"
+
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
new file mode 100644
index 000000000..51bc61c9e
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
@@ -0,0 +1,122 @@
+#!nsh
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.002
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.09
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 6.8
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.7
+ param set MPC_THR_MIN 0.3
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+set EXIT_ON_END no
+
+#
+# Start the Mikrokopter ESC driver
+#
+if [ $MKBLCTRL_MODE == yes ]
+then
+ if [ $MKBLCTRL_FRAME == x ]
+ then
+ echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing"
+ mkblctrl -mkmode x
+ else
+ echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing"
+ mkblctrl -mkmode +
+ fi
+else
+ if [ $MKBLCTRL_FRAME == x ]
+ then
+ echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame"
+ else
+ echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame"
+ fi
+ mkblctrl
+fi
+
+usleep 10000
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ 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)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+if [ $MKBLCTRL_FRAME == x ]
+then
+ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+else
+ mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
+fi
+
+#
+# Set PWM output frequency
+#
+#pwm -u 400 -m 0xff
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 040b5d594..c2a8c0c6a 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -84,7 +84,12 @@ then
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
- param load /fs/microsd/params
+ if param load /fs/microsd/params
+ then
+ echo "Parameters loaded"
+ else
+ echo "Parameter file corrupt - ignoring"
+ fi
fi
#fi
@@ -106,8 +111,13 @@ then
sh /etc/init.d/1000_rc.hil
set MODE custom
else
- # Try to get an USB console
- nshterm /dev/ttyACM0 &
+ if param compare SYS_AUTOSTART 1001
+ then
+ sh /etc/init.d/1001_rc_quad.hil
+ else
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
+ fi
fi
#
@@ -172,6 +182,42 @@ then
sh /etc/init.d/16_3dr_iris
set MODE custom
fi
+
+ # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame
+ if param compare SYS_AUTOSTART 17
+ then
+ set MKBLCTRL_MODE no
+ set MKBLCTRL_FRAME x
+ sh /etc/init.d/rc.custom_dji_f330_mkblctrl
+ set MODE custom
+ fi
+
+ # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame
+ if param compare SYS_AUTOSTART 18
+ then
+ set MKBLCTRL_MODE no
+ set MKBLCTRL_FRAME +
+ sh /etc/init.d/rc.custom_dji_f330_mkblctrl
+ set MODE custom
+ fi
+
+ # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing
+ if param compare SYS_AUTOSTART 19
+ then
+ set MKBLCTRL_MODE yes
+ set MKBLCTRL_FRAME x
+ sh /etc/init.d/rc.custom_dji_f330_mkblctrl
+ set MODE custom
+ fi
+
+ # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing
+ if param compare SYS_AUTOSTART 20
+ then
+ set MKBLCTRL_MODE yes
+ set MKBLCTRL_FRAME +
+ sh /etc/init.d/rc.custom_dji_f330_mkblctrl
+ set MODE custom
+ fi
if param compare SYS_AUTOSTART 30
then