#!/bin/sh
#
# @name Crazyflie 2.1
#
# @type Quadrotor x
# @class Copter
#
# @maintainer Dennis Shtatov <densht@gmail.com>
#
# @board px4_fmu-v2 exclude
# @board px4_fmu-v3 exclude
# @board px4_fmu-v4 exclude
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5 exclude
# @board px4_fmu-v5x exclude
# @board intel_aerofc-v1 exclude
#
. ${R}etc/init.d/rc.mc_defaults

set MIXER quad_x_cw
set PWM_OUT 1234
if [ $AUTOCNF = yes ]
then
	param set SYS_MC_EST_GROUP 3
	param set SYS_HAS_MAG 0

	param set BAT_N_CELLS 1
	param set BAT1_N_CELLS 1
	param set BAT1_SOURCE 1

	param set CBRK_SUPPLY_CHK 894281
	param set CBRK_USB_CHK 197848
	param set COM_RC_IN_MODE 1

	param set IMU_GYRO_CUTOFF 100
	param set IMU_ACCEL_CUTOFF 30

	param set MC_AIRMODE 1
	param set IMU_DGYRO_CUTOFF 70
	param set MC_PITCHRATE_D 0.002
	param set MC_PITCHRATE_I 0.2
	param set MC_PITCHRATE_P 0.07
	param set MC_PITCH_P 6.5
	param set MC_ROLLRATE_D 0.002
	param set MC_ROLLRATE_I 0.2
	param set MC_ROLLRATE_P 0.07
	param set MC_ROLL_P 6.5
	param set MC_YAW_P 3

	param set MPC_THR_HOVER 0.7
	param set MPC_THR_MAX 1
	param set MPC_Z_P 1.5
	param set MPC_Z_VEL_P_ACC 8
	param set MPC_Z_VEL_I_ACC 6
	param set MPC_HOLD_MAX_XY 0.1
	param set MPC_MAX_FLOW_HGT 3
	#param set IMU_GYRO_NF_FREQ 10
	#param set IMU_GYRO_NF_BW 20

	param set NAV_RCL_ACT 3

	param set PWM_MAIN_DISARM 0
	param set PWM_MAIN_MIN 0
	param set PWM_MAIN_MAX 255

	# Run the motors at 328.125 kHz (recommended)
	param set PWM_MAIN_RATE 3921

	param set SDLOG_PROFILE 1

	param set SENS_FLOW_MINRNG 0.05


fi

set PWM_MAIN_DISARM none
set PWM_MAIN_MAX none
set PWM_MAIN_MIN none

syslink start
mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000
