px4-firmware/ROMFS/px4fmu_common/init.d/4900_crazyflie

53 lines
1010 B
Plaintext
Raw Normal View History

#!nsh
#
# @name Crazyflie 2.0
#
2016-12-20 13:18:39 -04:00
# @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
#
2017-05-11 06:11:13 -03:00
# @maintainer Dennis Shtatov <densht@gmail.com>
#
2016-08-19 23:47:24 -03:00
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
2016-08-28 10:39:30 -03:00
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
2016-08-28 10:39:30 -03:00
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