You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
73 lines
1.2 KiB
73 lines
1.2 KiB
#!nsh |
|
|
|
echo "[init] 30_io_camflyer: PX4FMU+PX4IO on Camflyer" |
|
|
|
# |
|
# Load default params for this platform |
|
# |
|
if param compare SYS_AUTOCONFIG 1 |
|
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 MAVLink (depends on orb) |
|
# |
|
mavlink start -d /dev/ttyS1 -b 57600 |
|
usleep 5000 |
|
|
|
# |
|
# Start the commander (depends on orb, mavlink) |
|
# |
|
commander start |
|
|
|
# |
|
# Start PX4IO interface (depends on orb, commander) |
|
# |
|
px4io start |
|
|
|
# |
|
# Allow PX4IO to recover from midair restarts. |
|
# this is very unlikely, but quite safe and robust. |
|
px4io recovery |
|
|
|
# |
|
# Set actuator limit to 100 Hz update (50 Hz PWM) |
|
px4io limit 100 |
|
|
|
# |
|
# Start the sensors (depends on orb, px4io) |
|
# |
|
sh /etc/init.d/rc.sensors |
|
|
|
# |
|
# Start logging (depends on sensors) |
|
# |
|
sh /etc/init.d/rc.logging |
|
|
|
# |
|
# Start GPS interface (depends on orb) |
|
# |
|
gps start |
|
|
|
# |
|
# Start the attitude and position estimator |
|
# |
|
att_pos_estimator_ekf start |
|
|
|
# |
|
# Load mixer and start controllers (depends on px4io) |
|
# |
|
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix |
|
fw_att_control start |
|
fw_pos_control_l1 start
|
|
|