#!nsh # # @name Crazyflie 2.0 # # @board px4fmu-v2 exclude # @board px4fmu-v3 exclude # @board px4fmu-v4 exclude # @board px4fmu-v4pro exclude # @board px4fmu-v5 exclude # @board aerofc-v1 exclude # # @type Quadrotor x # @class Copter # # @maintainer Dennis Shtatov # sh /etc/init.d/4001_quad_x if [ $AUTOCNF == yes ] then param set COM_RC_IN_MODE 2 param set BAT_N_CELLS 1 param set BAT_CAPACITY 240 param set BAT_SOURCE 1 param set PWM_DISARMED 0 param set PWM_MIN 0 param set PWM_MAX 255 param set SYS_COMPANION 20 param set MC_PITCHRATE_D 0.0015 param set MC_PITCHRATE_I 0.05 param set MC_PITCHRATE_P 0.045 param set MC_PITCH_P 6.5 param set MC_ROLLRATE_D 0.0015 param set MC_ROLLRATE_I 0.05 param set MC_ROLLRATE_P 0.045 param set MC_ROLL_P 6.5 param set MC_YAW_P 3.0 param set CBRK_SUPPLY_CHK 894281 param set CBRK_USB_CHK 197848 fi set PWM_MIN none set PWM_MAX none set PWM_DISARMED none # Will run the motors at 328.125 kHz (recommended) set PWM_RATE 3921