Files
Beat Küng f454dcef6b ROMFS: set control allocation parameters for airframes
Removes some airframes:
- 1000_rc_fw_easystar.hil
- 10015_tbs_discovery
- 10016_3dr_iris
- 10018_tbs_endurance
- 13001_caipirinha_vtol
- 13002_firefly6
- 13003_quad_tailsitter
- 13004_quad+_tailsitter
- 13005_vtol_AAERT_quad
- 13006_vtol_standard_delta
- 13007_vtol_AAVVT_quad
- 13008_QuadRanger
- 13009_vtol_spt_ranger
- 13012_convergence
- 13050_generic_vtol_octo
- 14001_tri_y_yaw+
- 14002_tri_y_yaw-
- 15001_coax_heli
- 2105_maja
- 2200_mini_talon
- 3031_phantom
- 3032_skywalker_x5
- 3033_wingwing
- 3036_pigeon
- 3100_tbs_caipirinha
- 4003_qavr5
- 4009_qav250
- 4019_x500_v2
- 4030_3dr_solo
- 4031_3dr_quad
- 4051_s250aq
- 4072_draco
- 4080_zmr250
- 4090_nanomind
- 4100_tiltquadrotor
- 50003_aion_robotics_r1_rover
2022-08-12 09:43:12 +02:00

77 lines
1.8 KiB
Bash

#!/bin/sh
#
# @name Holybro Kopis 2
#
# @type Quadrotor x
# @class Copter
#
# @maintainer Beat Kueng <beat@px4.io>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT1_N_CELLS 4
param set-default GPS_1_CONFIG 0
param set-default RC_PORT_CONFIG 201
param set-default IMU_GYRO_CUTOFF 80
param set-default IMU_DGYRO_CUTOFF 50
param set-default IMU_GYRO_RATEMAX 2000
param set-default MC_ROLLRATE_P 0.085
param set-default MC_ROLLRATE_I 0.25
param set-default MC_ROLLRATE_D 0.0008
param set-default MC_ROLLRATE_MAX 1600
param set-default MC_ROLL_P 10
param set-default MC_PITCHRATE_P 0.085
param set-default MC_PITCHRATE_I 0.32
param set-default MC_PITCHRATE_D 0.0008
param set-default MC_PITCHRATE_MAX 1600
param set-default MC_PITCH_P 10
param set-default MC_YAWRATE_MAX 1000
param set-default MC_YAWRATE_P 0.15
param set-default MC_YAW_P 4
param set-default MPC_MANTHR_MIN 0
param set-default MPC_MAN_TILT_MAX 60
param set-default OSD_ATXXXX_CFG 1
param set-default TEL_FRSKY_CONFIG 300
param set-default THR_MDL_FAC 0.35
param set-default MPC_THR_CURVE 1
param set-default MPC_THR_HOVER 0.12
param set-default MC_AIRMODE 1
param set-default EV_TSK_RC_LOSS 1
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
param set-default CA_ROTOR0_PY 0.15
param set-default CA_ROTOR1_PX -0.15
param set-default CA_ROTOR1_PY -0.15
param set-default CA_ROTOR2_PX 0.15
param set-default CA_ROTOR2_PY -0.15
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.15
param set-default CA_ROTOR3_PY 0.15
param set-default CA_ROTOR3_KM -0.05
param set-default PWM_MAIN_FUNC1 104
param set-default PWM_MAIN_FUNC2 101
param set-default PWM_MAIN_FUNC3 102
param set-default PWM_MAIN_FUNC4 103
param set-default PWM_MAIN_TIM0 -2
param set-default PWM_MAIN_TIM1 -2