|
楼主 |
发表于 2015-1-8 23:29
|
显示全部楼层
本帖最后由 skypup 于 2015-1-8 23:32 编辑
config.h 似乎主要改了3处:
1 修改:
#define MINCOMMAND -1056 // 可能与 EXT_MOTOR_RANGE 相关
2 在 IMU 下增加:
#define HEX_NANO // Flexbot 使用Mega32U4 MPU6050, HMC5883L, BMP085
3 在 SECTION 3 - RC SYSTEM SETUP 下增加:
#define RCSERIAL
#ifndef CONFIG_H_
#define CONFIG_H_
/*************************************************************************************************/
/**** 参数配置 ****/
/*************************************************************************************************/
/* 以下第1组配置为必选项
* 1 - BASIC SETUP - 基本设置,必选项。
* 2 - COPTER TYPE SPECIFIC OPTIONS - 飞行器类型
* 3 - RC SYSTEM SETUP - 遥控器
* 4 - ALTERNATE CPUs & BOARDS - 非典型MCU, IMU
* 5 - ALTERNATE SETUP - 非典型接口,如 S.BUS 接收器, 特殊的电调, 等等。
* 6 - OPTIONAL FEATURES - 扩展设置,如电压、报警,等等。
* 7 - TUNING & DEVELOPER - 开发人员选项,仅针高级用户
* 8 - DEPRECATED - these features will be removed in some future release
*/
/* PS:
* 1. 有 (*) 标记的项目, 保存在 EEPROM. 可以通过串口调试助手修改。
* 2. 有 (**) 标记的项目,保存在 EEPROM,可以在 WinGUI 软件界面设置。
*/
/*************************************************************************************************/
/***************** ***************/
/**************** SECTION 1 - BASIC SETUP - 基本设置,必选项。 *******/
/***************** ***************/
/*************************************************************************************************/
/************************** 飞行器类型 ****************************/
//#define GIMBAL
//#define BI
//#define TRI
//#define QUADP
//#define QUADX // 修改过混控
//#define Y4
//#define Y6
//#define HEX6
//#define HEX6X // 修改过混控,适合系留平台
//#define HEX6H
//#define OCTOX8
//#define OCTOFLATP
//#define OCTOFLATX
//#define FLYING_WING
//#define VTAIL4
#define AIRPLANE
//#define SINGLECOPTER
//#define DUALCOPTER
//#define HELI_120_CCPM
//#define HELI_90_DEG
/**************************** 油门 *******************************/
// 怠速油门
#define MINTHROTTLE 1000 // (*) (**)
// 全油门
#define MAXTHROTTLE 2000
// 熄火油门
#define MINCOMMAND 950
/********************************** I2C speed ************************************/
//#define I2C_SPEED 100000L //100kHz normal mode, this value must be used for a genuine WMP
#define I2C_SPEED 400000L //400kHz fast mode, it works only with some WMP clones
/*************************** I2C 内部上拉 (建议在电路板上使用外部上拉电阻) ********************************/
//#define INTERNAL_I2C_PULLUPS
/**************************************************************************************/
/***************** IMU ******************/
/**************************************************************************************/
/*************************** 组合 IMU 板********************************/
//#define FFIMUv1 // first 9DOF+baro board from Jussi, with HMC5843 <- confirmed by Alex
//#define FFIMUv2 // second version of 9DOF+baro board from Jussi, with HMC5883 <- confirmed by Alex
//#define FREEIMUv1 // v0.1 & v0.2 & v0.3 version of 9DOF board from Fabio
//#define FREEIMUv03 // FreeIMU v0.3 and v0.3.1
//#define FREEIMUv035 // FreeIMU v0.3.5 no baro
//#define FREEIMUv035_MS // FreeIMU v0.3.5_MS <- confirmed by Alex
//#define FREEIMUv035_BMP // FreeIMU v0.3.5_BMP
//#define FREEIMUv04 // FreeIMU v0.4 with MPU6050, HMC5883L, MS561101BA <- confirmed by Alex
//#define FREEIMUv043 // same as FREEIMUv04 with final MPU6050 (with the right ACC scale)
//#define NANOWII // the smallest multiwii FC based on MPU6050 + pro micro based proc <- confirmed by Alex
//#define PIPO // 9DOF board from erazz
//#define QUADRINO // full FC board 9DOF+baro board from witespy with BMP085 baro <- confirmed by Alex
//#define QUADRINO_ZOOM // full FC board 9DOF+baro board from witespy second edition
//#define QUADRINO_ZOOM_MS// full FC board 9DOF+baro board from witespy second edition <- confirmed by Alex
//#define ALLINONE // full FC board or standalone 9DOF+baro board from CSG_EU
//#define AEROQUADSHIELDv2
//#define ATAVRSBIN1 // Atmel 9DOF (Contribution by EOSBandi). requires 3.3V power.
//#define SIRIUS // Sirius Navigator IMU <- confirmed by Alex
//#define SIRIUSGPS // Sirius Navigator IMU using external MAG on GPS board <- confirmed by Alex
//#define SIRIUS600 // Sirius Navigator IMU using the WMP for the gyro
//#define SIRIUS_MEGAv5_OSD // Paris_Sirius™ ITG3050,BMA280,MS5611,HMC5883,uBlox http://www.Multiwiicopter.com <- confirmed by Alex
//#define MINIWII // Jussi's MiniWii Flight Controller <- confirmed by Alex
//#define CITRUSv2_1 // CITRUS from qcrc.ca
//#define CHERRY6DOFv1_0
//#define DROTEK_10DOF // Drotek 10DOF with ITG3200, BMA180, HMC5883, BMP085, w or w/o LLC
//#define DROTEK_10DOF_MS // Drotek 10DOF with ITG3200, BMA180, HMC5883, MS5611, LLC
//#define DROTEK_6DOFv2 // Drotek 6DOF v2
//#define DROTEK_6DOF_MPU // Drotek 6DOF with MPU6050
//#define DROTEK_10DOF_MPU//
//#define MONGOOSE1_0 // mongoose 1.0 http://store.ckdevices.com/
//#define CRIUS_LITE // Crius MultiWii Lite
//#define CRIUS_SE // Crius MultiWii SE
//#define CRIUS_SE_v2_0 // Crius MultiWii SE 2.0 with MPU6050, HMC5883 and BMP085
//#define OPENLRSv2MULTI // OpenLRS v2 Multi Rc Receiver board including ITG3205 and ADXL345
//#define BOARD_PROTO_1 // with MPU6050 + HMC5883L + MS baro
//#define BOARD_PROTO_2 // with MPU6050 + slave MAG3110 + MS baro
//#define GY_80 // Chinese 10 DOF with L3G4200D ADXL345 HMC5883L BMP085, LLC
//#define GY_85 // Chinese 9 DOF with ITG3205 ADXL345 HMC5883L LLC
//#define GY_86 // Chinese 10 DOF with MPU6050 HMC5883L MS5611, LLC
#define GY_521 // Chinese 6 DOF with MPU6050, LLC
//#define INNOVWORKS_10DOF // with ITG3200, BMA180, HMC5883, BMP085 available here http://www.diymulticopter.com
//#define INNOVWORKS_6DOF // with ITG3200, BMA180 available here http://www.diymulticopter.com
//#define MultiWiiMega // MEGA + MPU6050+HMC5883L+MS5611 available here http://www.diymulticopter.com
//#define PROTO_DIY // 10DOF mega board
//#define IOI_MINI_MULTIWII// www.bambucopter.com
//#define Bobs_6DOF_V1 // BobsQuads 6DOF V1 with ITG3200 & BMA180
//#define Bobs_9DOF_V1 // BobsQuads 9DOF V1 with ITG3200, BMA180 & HMC5883L
//#define Bobs_10DOF_BMP_V1 // BobsQuads 10DOF V1 with ITG3200, BMA180, HMC5883L & BMP180 - BMP180 is software compatible with BMP085
//#define FLYDUINO_MPU // MPU6050 Break Out onboard 3.3V reg
//#define CRIUS_AIO_PRO_V1
//#define DESQUARED6DOFV2GO // DEsquared V2 with ITG3200 only
//#define DESQUARED6DOFV4 // DEsquared V4 with MPU6050
//#define LADYBIRD
//#define MEGAWAP_V2_STD // available here: http://www.multircshop.com <- confirmed by Alex
//#define MEGAWAP_V2_ADV
//#define HK_MultiWii_SE_V2 // Hobbyking board with MPU6050 + HMC5883L + BMP085
//#define HK_MultiWii_328P // Also labeled "Hobbybro" on the back. ITG3205 + BMA180 + BMP085 + NMC5583L + DSM2 Connector (Spektrum Satellite)
//#define RCNet_FC // RCNet FC with MPU6050 and MS561101BA http://www.rcnet.com
//#define RCNet_FC_GPS // RCNet FC with MPU6050 + MS561101BA + HMC5883L + UBLOX GPS http://www.rcnet.com
//#define FLYDU_ULTRA // MEGA+10DOF+MT3339 FC
//#define DIYFLYING_MAGE_V1 // diyflying 10DOF mega board with MPU6050 + HMC5883L + BMP085 http://www.indoor-flying.hk
//#define Flyduino9DOF // Flyduino 9DOF IMU MPU6050+HMC5883l
//#define Nano_Plane // Multiwii Plane version with tail-front LSM330 sensor http://www.radiosait.ru/en/page_5324.html
//#define HEX_NANO // Flexbot 使用Mega32U4 MPU6050, HMC5883L, BMP085
/*************************** 独立传感器 ********************************/
/* 如果已经定义了组合 IMU 以下保持为注释状态即可, 在 def.h 中会做处理 */
/* I2C gyroscope 陀螺仪 */
//#define WMP
//#define ITG3200
//#define MPU3050
//#define L3G4200D
//#define MPU6050 //combo + ACC
//#define LSM330 //combo + ACC
/* I2C accelerometer 加速度计 */
//#define NUNCHUCK // if you want to use the nunckuk connected to a WMP
//#define MMA7455
//#define ADXL345
//#define BMA020
//#define BMA180
//#define BMA280
//#define NUNCHACK // if you want to use the nunckuk as a standalone I2C ACC without WMP
//#define LIS3LV02
//#define LSM303DLx_ACC
//#define MMA8451Q
/* I2C barometer 气压传感器 */
//#define BMP085
//#define MS561101BA
/* I2C magnetometer 地磁传感器 */
//#define HMC5843
//#define HMC5883
//#define AK8975
//#define MAG3110
/* Sonar 声纳 */ // for visualization purpose currently - no control code behind
//#define SRF02 // use the Devantech SRF i2c sensors
//#define SRF08
//#define SRF10
//#define SRF23
/* enforce your individual sensor orientation - even overrides board specific defaults 传感器安装方向定义 */
//#define FORCE_ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = Y; imu.accADC[PITCH] = -X; imu.accADC[YAW] = Z;}
//#define FORCE_GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -Y; imu.gyroADC[PITCH] = X; imu.gyroADC[YAW] = Z;}
//#define FORCE_MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = Z;}
/* Board orientation shift */
/* If you have frame designed only for + mode and you cannot rotate FC phisycally for flying in X mode (or vice versa)
* you can use one of of this options for virtual sensors rotation by 45 deegres, then set type of multicopter according to flight mode.
* Check motors order and directions of motors rotation for matching with new front point! Uncomment only one option! */
//#define SENSORS_TILT_45DEG_RIGHT // rotate the FRONT 45 degres clockwise
//#define SENSORS_TILT_45DEG_LEFT // rotate the FRONT 45 degres counterclockwise
/*************************************************************************************************/
/***************** ***************/
/**************** SECTION 2 - 2 - COPTER TYPE SPECIFIC OPTIONS - 飞行器类型 *******/
/***************** ***************/
/*************************************************************************************************/
/******************************** PID Controller *********************************/
/* PID 算法选择
* 1 = 经典 PID 算法 (与 V2.2 一致)
* 2 = new experimental algorithm from Alex Khoroshko - unsupported - http://www.multiwii.com/forum/vi ... amp;start=10#p37387
* */
#define PID_CONTROLLER 1
/* NEW: not used anymore for servo coptertypes <== NEEDS FIXING - MOVE TO WIKI */
#define YAW_DIRECTION 1
//#define YAW_DIRECTION -1 // if you want to reverse the yaw correction direction
#define ONLYARMWHENFLAT //prevent the copter from arming when the copter is tilted - 飞机倾斜时不允许加锁
/******************************** 解锁/加锁 *********************************/
/* 可选,使用遥控手柄组合操作方式解锁/加锁.
* 一般的,选用以下方式之一即可. */
//#define ALLOW_ARM_DISARM_VIA_TX_YAW
//#define ALLOW_ARM_DISARM_VIA_TX_ROLL
/******************************** 舵机 *********************************/
/* info on which servos connect where and how to setup can be found here
* http://www.multiwii.com/wiki/ind ... ervos_configuration
* 设置舵机 End Point, 中立点, 正反向 */
//#define SERVO_MIN {1020, 1020, 1020, 1020, 1020, 1020, 1020, 1020}
//#define SERVO_MAX {2000, 2000, 2000, 2000, 2000, 2000, 2000, 2000}
//#define SERVO_MID {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500} // (*)
//#define FORCE_SERVO_RATES {30,30,100,100,100,100,100,100} // 0 = normal, 1= reverse
/*********************** Cam Stabilisation 云台 ***********************/
/* The following lines apply only for a pitch/roll tilt stabilization system. Uncomment the first or second line to activate it */
/* 开启俯仰/横滚方向的两轴云台,反注释其中一项来激活它 */
//#define SERVO_MIX_TILT
//#define SERVO_TILT
/* camera trigger function 相机拍照功能: activated via Rc Options in the GUI, servo output=A2 on promini */
// trigger interval can be changed via (*GUI*) or via AUX channel
//#define CAMTRIG
#define CAM_TIME_HIGH 1000 // the duration of HIGH state servo expressed in ms
/*********************** Airplane 固定翼 ***********************/
#define USE_THROTTLESERVO // 油门使用 50Hz PWM 信号
//#define FLAPPERONS AUX4 // Mix Flaps with Aileroins.
#define FLAPPERON_EP { 1500, 1700 } // Endpooints for flaps on a 2 way switch else set {1020,2000} and program in radio.
#define FLAPPERON_INVERT { -1, 1 } // Change direction om flapperons { Wing1, Wing2 }
//#define FLAPS // Traditional Flaps on SERVO3.
//#define FLAPSPEED 3 // Make flaps move slowm Higher value is Higher Speed.
/*********************** Common for Heli & Airplane ***********************/
/* Governor: attempts to maintain rpm through pitch and voltage changes
* predictive approach: observe input signals and voltage and guess appropriate corrections.
* (the throttle curve must leave room for the governor, so 0-50-75-80-80 is ok, 0-50-95-100-100 is _not_ ok.
* Can be toggled via aux switch.
*/
//#define GOVERNOR_P 7 // (*) proportional factor. Higher value -> higher throttle increase. Must be >=1; 0 = turn off
//#define GOVERNOR_D 4 // (*) decay timing. Higher value -> takes longer to return throttle to normal. Must be >=1;
//#define VOLTAGEDROP_COMPENSATION // voltage impact correction
/*********************** Heli ***********************/
/* Channel to control CollectivePitch */
#define COLLECTIVE_PITCH THROTTLE
/* Limit the range of Collective Pitch. 100% is Full Range each way and position for Zero Pitch */
#define COLLECTIVE_RANGE { 80, 0, 80 }// {Min%, ZeroPitch offset from 1500, Max%}.
#define YAWMOTOR 0 // If a motor is used as YAW Set to 1 else set to 0.
/* Servo mixing for heli 120
{Coll,Nick,Roll} */
#define SERVO_NICK { +10, -10, 0 }
#define SERVO_LEFT { +10, +5, +10 }
#define SERVO_RIGHT { +10, +5, -10 }
/* Limit Maximum controll for Roll & Nick in 0-100% */
#define CONTROL_RANGE { 100, 100 } // { ROLL,PITCH }
/* use servo code to drive the throttle output. You want this for analog servo driving the throttle on IC engines.
if inactive, throttle output will be treated as a motor output, so it can drive an ESC */
//#define HELI_USE_SERVO_FOR_THROTTLE
/*********************** your individual mixing ***********************/
/* if you want to override an existing entry in the mixing table, you may want to avoid editing the
* mixTable() function for every version again and again.
* howto: http://www.multiwii.com/wiki/ind ... h#Individual_Mixing
*/
//#define MY_PRIVATE_MIXING "filename.h"
/*********************** your individual defaults ***********************/
/* if you want to replace the hardcoded default values with your own (e.g. from a previous save to an .mwi file),
* you may want to avoid editing the LoadDefaults() function for every version again and again.
* http://www.multiwii.com/wiki/ind ... Individual_defaults
*/
//#define MY_PRIVATE_DEFAULTS "filename.h"
/*************************************************************************************************/
/***************** ***************/
/**************** SECTION 3 - RC SYSTEM SETUP - 遥控器 *******/
/***************** ***************/
/*************************************************************************************************/
/**************************** PPM Sum Reciver ***********************************/
/* The following lines apply only for specific receiver with only one PPM sum signal, on digital PIN 2
Select the right line depending on your radio brand. Feel free to modify the order in your PPM order is different */
//#define SERIAL_SUM_PPM PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,AUX3,AUX4,8,9,10,11 //For Graupner/Spektrum
//#define SERIAL_SUM_PPM ROLL,PITCH,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4,8,9,10,11 //For Robe/Hitec/Futaba
//#define SERIAL_SUM_PPM ROLL,PITCH,YAW,THROTTLE,AUX1,AUX2,AUX3,AUX4,8,9,10,11 //For Multiplex
#define SERIAL_SUM_PPM PITCH,ROLL,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4,8,9,10,11 //For some Hitec/Sanwa/Others
// Uncommenting following line allow to connect PPM_SUM receiver to standard THROTTLE PIN on MEGA boards (eg. A8 in CRIUS AIO)
#define PPM_ON_THROTTLE
/********************** Spektrum Satellite Reciver *******************************/
/* The following lines apply only for Spektrum Satellite Receiver
Spektrum Satellites are 3V devices. DO NOT connect to 5V!
For MEGA boards, attach sat grey wire to RX1, pin 19. Sat black wire to ground. Sat orange wire to Mega board's 3.3V (or any other 3V to 3.3V source).
For PROMINI, attach sat grey to RX0. Attach sat black to ground. */
//#define SPEKTRUM 1024
//#define SPEKTRUM 2048
//#define SPEK_SERIAL_PORT 1 // Forced to 0 on Pro Mini and single serial boards; Set to your choice of 0, 1, or 2 on any Mega based board (defaults to 1 on Mega).
//**************************
// Defines that allow a "Bind" of a Spektrum or Compatible Remote Receiver (aka Satellite) via Configuration GUI.
// Bind mode will be same as declared above, if your TX is capable.
// Ground, Power, and Signal must come from three adjacent pins.
// By default, these are Ground=4, Power=5, Signal=6. These pins are in a row on most MultiWii shield boards. Pins can be overriden below.
// Normally use 3.3V regulator is needed on the power pin!! If your satellite hangs during bind (blinks, but won't complete bind with a solid light), go direct 5V on all pins.
//**************************
// For Pro Mini, the connector for the Satellite that resides on the FTDI can be unplugged and moved to these three adjacent pins.
//#define SPEK_BIND //Un-Comment for Spektrum Satellie Bind Support. Code is ~420 bytes smaller without it.
//#define SPEK_BIND_GROUND 4
//#define SPEK_BIND_POWER 5
//#define SPEK_BIND_DATA 6
/******************************* Futaba S.BUS 接收器 ************************************/
/* The following line apply only for Futaba S-Bus Receiver on MEGA boards at RX1 only (Serial 1).
You have to invert the S-Bus-Serial Signal e.g. with a Hex-Inverter like IC SN74 LS 04 */
//#define SBUS
#define SBUS_SERIAL_PORT 1
#define SBUS_MID_OFFSET 988 //SBUS Mid-Point at 1500
/******************************* 使用串口数据遥控 ************************************/
#define RCSERIAL
/*************************************************************************************************/
/***************** ***************/
/**************** SECTION 4 - ALTERNATE CPUs & BOARDS - 非典型MCU, IMU *******/
/***************** ***************/
/*************************************************************************************************/
/**************************************************************************************/
/******** Promini Specifig Settings ********************/
/**************************************************************************************/
/************************** Hexa Motor 5 & 6 Pins *******************************/
/* PIN A0 and A1 instead of PIN D5 & D6 for 6 motors config and promini config
This mod allow the use of a standard receiver on a pro mini */
//#define A0_A1_PIN_HEX
/********************************* Aux 2 Pin ***********************************/
/* possibility to use PIN8 or PIN12 as the AUX2 RC input (only one, not both)
it deactivates in this case the POWER PIN (pin 12) or the BUZZER PIN (pin 8) */
//#define RCAUXPIN8
//#define RCAUXPIN12
/**************************************************************************************/
/***************** Teensy 2.0 Support ******************/
/**************************************************************************************/
/* uncomment this if you use a teensy 2.0 with teensyduino
it needs to run at 16MHz */
//#define TEENSY20
/**************************************************************************************/
/******** Settings for ProMicro, Leonardo and other Atmega32u4 Boards ***********/
/**************************************************************************************/
/********************************* pin Layout **********************************/
/* activate this for a better pinlayout if all pins can be used => not possible on ProMicro */
#define A32U4ALLPINS
/********************************** PWM Setup **********************************/
/* activate all 6 hardware PWM outputs Motor 5 = D11 and 6 = D13.
note: not possible on the sparkfun promicro (pin 11 & 13 are not broken out there)
if activated:
Motor 1-6 = 10-bit hardware PWM
Motor 7-8 = 8-bit Software PWM
Servos = 8-bit Software PWM
if deactivated:
Motor 1-4 = 10-bit hardware PWM
Motor 5-8 = 10-bit Software PWM
Servos = 10-bit Software PWM */
#define HWPWM6
/********************************** Aux 2 Pin **********************************/
/* AUX2 pin on pin RXO */
//#define RCAUX2PINRXO
/* aux2 pin on pin D17 (RXLED) */
//#define RCAUX2PIND17
/********************************** Buzzer Pin **********************************/
/* this moves the Buzzer pin from TXO to D8 for use with ppm sum or spectrum sat. RX (not needed if A32U4ALLPINS is active) */
//#define D8BUZZER
/*********************** Promicro version related ****************************/
/* Inverted status LED for Promicro ver 10 */
//#define PROMICRO10
/**************************************************************************************/
/******** 修改管脚定义 ********************/
/**************************************************************************************/
/* only enable any of this if you must change the default pin assignment, e.g. your board does not have a specific pin */
/* you may need to change PINx and PORTx plus #shift according to the desired pin! */
//#define OVERRIDE_V_BATPIN A0 // instead of A3 // Analog PIN 3
//#define OVERRIDE_PSENSORPIN A1 // instead of A2 // Analog PIN 2
//#define OVERRIDE_LEDPIN_PINMODE pinMode (A1, OUTPUT); // use A1 instead of d13
//#define OVERRIDE_LEDPIN_TOGGLE PINC |= 1<<1; // PINB |= 1<<5; //switch LEDPIN state (digital PIN 13)
//#define OVERRIDE_LEDPIN_OFF PORTC &= ~(1<<1); // PORTB &= ~(1<<5);
//#define OVERRIDE_LEDPIN_ON PORTC |= 1<<1; // was PORTB |= (1<<5);
//#define OVERRIDE_BUZZERPIN_PINMODE pinMode (A2, OUTPUT); // use A2 instead of d8
//#define OVERRIDE_BUZZERPIN_ON PORTC |= 1<<2 //PORTB |= 1;
//#define OVERRIDE_BUZZERPIN_OFF PORTC &= ~(1<<2); //PORTB &= ~1;
/*************************************************************************************************/
/***************** ***************/
/**************** SECTION 5 - 非典型接口,如 S.BUS 接收器, 特殊的电调, 等等。 *******/
/***************** ***************/
/*************************************************************************************************/
/****** 串口波特率 *********************************/
#define SERIAL0_COM_SPEED 38400
#define SERIAL1_COM_SPEED 38400
#define SERIAL2_COM_SPEED 57600
#define SERIAL3_COM_SPEED 38400
/* interleaving delay in micro seconds between 2 readings WMP/NK in a WMP+NK config
if the ACC calibration time is very long (20 or 30s), try to increase this delay up to 4000
it is relevent only for a conf with NK */
#define INTERLEAVING_DELAY 3000
/* when there is an error on I2C bus, we neutralize the values during a short time. expressed in microseconds
it is relevent only for a conf with at least a WMP */
#define NEUTRALIZE_DELAY 100000
/**************************************************************************************/
/******** Gyro filters ********************/
/**************************************************************************************/
/********************* Lowpass filter for some gyros ****************************/
/* ITG3200 & ITG3205 Low pass filter setting. In case you cannot eliminate all vibrations to the Gyro, you can try
to decrease the LPF frequency, only one step per try. As soon as twitching gone, stick with that setting.
It will not help on feedback wobbles, so change only when copter is randomly twiching and all dampening and
balancing options ran out. Uncomment only one option!
IMPORTANT! Change low pass filter setting changes PID behaviour, so retune your PID's after changing LPF.*/
//#define ITG3200_LPF_256HZ // This is the default setting, no need to uncomment, just for reference
//#define ITG3200_LPF_188HZ
//#define ITG3200_LPF_98HZ
//#define ITG3200_LPF_42HZ
//#define ITG3200_LPF_20HZ
//#define ITG3200_LPF_10HZ // Use this only in extreme cases, rather change motors and/or props
/* MPU6050 Low pass filter setting. In case you cannot eliminate all vibrations to the Gyro, you can try
to decrease the LPF frequency, only one step per try. As soon as twitching gone, stick with that setting.
It will not help on feedback wobbles, so change only when copter is randomly twiching and all dampening and
balancing options ran out. Uncomment only one option!
IMPORTANT! Change low pass filter setting changes PID behaviour, so retune your PID's after changing LPF.*/
//#define MPU6050_LPF_256HZ // This is the default setting, no need to uncomment, just for reference
//#define MPU6050_LPF_188HZ
//#define MPU6050_LPF_98HZ
#define MPU6050_LPF_42HZ
//#define MPU6050_LPF_20HZ
//#define MPU6050_LPF_10HZ
//#define MPU6050_LPF_5HZ // Use this only in extreme cases, rather change motors and/or props
/****** Gyro smoothing **********************************/
/* GYRO_SMOOTHING. In case you cannot reduce vibrations _and_ _after_ you have tried the low pass filter options, you
may try this gyro smoothing via averaging. Not suitable for multicopters!
Good results for helicopter, airplanes and flying wings (foamies) with lots of vibrations.*/
//#define GYRO_SMOOTHING {20, 20, 3} // (*) separate averaging ranges for roll, pitch, yaw
/************************ Moving Average Gyros **********************************/
#define MMGYRO 10 // (*) Active Moving Average Function for Gyros
#define MMGYROVECTORLENGTH 15 // Length of Moving Average Vector (maximum value for tunable MMGYRO
/* Moving Average ServoGimbal Signal Output */
//#define MMSERVOGIMBAL // Active Output Moving Average Function for Servos Gimbal
//#define MMSERVOGIMBALVECTORLENGHT 32 // Lenght of Moving Average Vector
/************************ Analog Reads **********************************/
/* if you want faster analog Reads, enable this. It may result in less accurate results, especially for more than one analog channel */
//#define FASTER_ANALOG_READS
|
|