#!nsh echo "[init] 10_io_f330: PX4FMU+PX4IO on a DJI F330 quad frame" # # 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.004 param set MC_ATTRATE_I 0.0 param set MC_ATTRATE_P 0.12 param set MC_ATT_D 0.0 param set MC_ATT_I 0.0 param set MC_ATT_P 7.0 param set MC_RCLOSS_THR 0.0 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 save /fs/microsd/params fi # # Force some key parameters to sane values # MAV_TYPE 2 = quadrotor # param set MAV_TYPE 2 # # Start MAVLink (depends on orb) # mavlink start usleep 5000 # # Start and configure PX4IO interface # 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 # # Load mixer # mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix # # Set PWM output frequency # pwm -u 400 -m 0xff # # Start common for all multirotors apps # sh /etc/init.d/rc.multirotor