mwc飞控配置功能速查
0.说明
记录mwc飞控各个功能的配置使用情况.
所有代码基于mwc2.3
- 飞行模式选择
1 //#define GIMBAL // 云台 2 //#define BI // 阿凡达模式 3 //#define TRI // 3轴模式 4 //#define QUADP // +四轴 5 #define QUADX // x四轴 6 //#define Y4 // Y4轴模式 7 //#define Y6 // Y6轴模式 8 //#define HEX6 // 平面6轴+模式 9 //#define HEX6X // 平面6轴x模式 10 //#define HEX6H // New Model 11 //#define OCTOX8 12 //#define OCTOFLATP 13 //#define OCTOFLATX 14 //#define FLYING_WING //飞翼 15 //#define VTAIL4 16 //#define AIRPLANE 17 //#define SINGLECOPTER 18 //#define DUALCOPTER 19 //#define HELI_120_CCPM 20 //#define HELI_90_DEG
- 最小油门速度(怠速)
#define MINTHROTTLE 1150 // (*) (**)
- 最大油门速度
#define MAXTHROTTLE 1850
- 未解锁时油门速度
#define MINCOMMAND 1000
- 高速I2C模式
#define I2C_SPEED 400000L //400kHz fast mode, it works only with some WMP clones
- 循环时间(飞控进行一次姿态检测,姿态解算,输出控制等等操作的时间)
#define LOOP_TIME 2800
- 传感器板选择
1 /*************************** Combined IMU Boards ********************************/ 2 /* if you use a specific sensor board: 3 please submit any correction to this list. 4 Note from Alex: I only own some boards, for other boards, I'm not sure, the info was gathered via rc forums, be cautious */ 5 //#define FFIMUv1 // first 9DOF+baro board from Jussi, with HMC5843 <- confirmed by Alex 6 //#define FFIMUv2 // second version of 9DOF+baro board from Jussi, with HMC5883 <- confirmed by Alex 7 //#define FREEIMUv1 // v0.1 & v0.2 & v0.3 version of 9DOF board from Fabio 8 //#define FREEIMUv03 // FreeIMU v0.3 and v0.3.1 9 //#define FREEIMUv035 // FreeIMU v0.3.5 no baro 10 //#define FREEIMUv035_MS // FreeIMU v0.3.5_MS <- confirmed by Alex 11 //#define FREEIMUv035_BMP // FreeIMU v0.3.5_BMP 12 //#define FREEIMUv04 // FreeIMU v0.4 with MPU6050, HMC5883L, MS561101BA <- confirmed by Alex 13 //#define FREEIMUv043 // same as FREEIMUv04 with final MPU6050 (with the right ACC scale) 14 //#define NANOWII // the smallest multiwii FC based on MPU6050 + pro micro based proc <- confirmed by Alex 15 //#define PIPO // 9DOF board from erazz 16 //#define QUADRINO // full FC board 9DOF+baro board from witespy with BMP085 baro <- confirmed by Alex 17 //#define QUADRINO_ZOOM // full FC board 9DOF+baro board from witespy second edition 18 //#define QUADRINO_ZOOM_MS// full FC board 9DOF+baro board from witespy second edition <- confirmed by Alex 19 //#define ALLINONE // full FC board or standalone 9DOF+baro board from CSG_EU 20 //#define AEROQUADSHIELDv2 21 //#define ATAVRSBIN1 // Atmel 9DOF (Contribution by EOSBandi). requires 3.3V power. 22 //#define SIRIUS // Sirius Navigator IMU <- confirmed by Alex 23 //#define SIRIUSGPS // Sirius Navigator IMU using external MAG on GPS board <- confirmed by Alex 24 //#define SIRIUS600 // Sirius Navigator IMU using the WMP for the gyro 25 //#define SIRIUS_AIR // Sirius Navigator IMU 6050 32U4 from MultiWiiCopter.com <- confirmed by Alex 26 //#define SIRIUS_AIR_GPS // Sirius Navigator IMU 6050 32U4 from MultiWiiCopter.com with GPS/MAG remote located 27 //#define SIRIUS_MEGAv5_OSD // Paris_Sirius鈩�ITG3050,BMA280,MS5611,HMC5883,uBlox http://www.Multiwiicopter.com <- confirmed by Alex 28 //#define MINIWII // Jussi's MiniWii Flight Controller <- confirmed by Alex 29 //#define MICROWII // MicroWii 10DOF with ATmega32u4, MPU6050, HMC5883L, MS561101BA from http://flyduino.net/ 30 //#define CITRUSv2_1 // CITRUS from qcrc.ca 31 //#define CHERRY6DOFv1_0 32 //#define DROTEK_10DOF // Drotek 10DOF with ITG3200, BMA180, HMC5883, BMP085, w or w/o LLC 33 //#define DROTEK_10DOF_MS // Drotek 10DOF with ITG3200, BMA180, HMC5883, MS5611, LLC 34 //#define DROTEK_6DOFv2 // Drotek 6DOF v2 35 //#define DROTEK_6DOF_MPU // Drotek 6DOF with MPU6050 36 //#define DROTEK_10DOF_MPU// 37 //#define MONGOOSE1_0 // mongoose 1.0 http://store.ckdevices.com/ 38 //#define CRIUS_LITE // Crius MultiWii Lite 39 //#define CRIUS_SE // Crius MultiWii SE 40 //#define CRIUS_SE_v2_0 // Crius MultiWii SE 2.0 with MPU6050, HMC5883 and BMP085 41 //#define OPENLRSv2MULTI // OpenLRS v2 Multi Rc Receiver board including ITG3205 and ADXL345 42 //#define BOARD_PROTO_1 // with MPU6050 + HMC5883L + MS baro 43 //#define BOARD_PROTO_2 // with MPU6050 + slave MAG3110 + MS baro 44 //#define GY_80 // Chinese 10 DOF with L3G4200D ADXL345 HMC5883L BMP085, LLC 45 //#define GY_85 // Chinese 9 DOF with ITG3205 ADXL345 HMC5883L LLC 46 #define GY_86 // Chinese 10 DOF with MPU6050 HMC5883L MS5611, LLC 47 // uncomment at 2015-5-30 09:08:37 48 //#define GY_88 // Chinese 10 DOF with MPU6050 HMC5883L BMP085, LLC 49 //#define GY_521 // Chinese 6 DOF with MPU6050, LLC 50 //#define INNOVWORKS_10DOF // with ITG3200, BMA180, HMC5883, BMP085 available here http://www.diymulticopter.com 51 //#define INNOVWORKS_6DOF // with ITG3200, BMA180 available here http://www.diymulticopter.com 52 //#define MultiWiiMega // MEGA + MPU6050+HMC5883L+MS5611 available here http://www.diymulticopter.com 53 //#define PROTO_DIY // 10DOF mega board 54 //#define IOI_MINI_MULTIWII// www.bambucopter.com 55 //#define Bobs_6DOF_V1 // BobsQuads 6DOF V1 with ITG3200 & BMA180 56 //#define Bobs_9DOF_V1 // BobsQuads 9DOF V1 with ITG3200, BMA180 & HMC5883L 57 //#define Bobs_10DOF_BMP_V1 // BobsQuads 10DOF V1 with ITG3200, BMA180, HMC5883L & BMP180 - BMP180 is software compatible with BMP085 58 //#define FLYDUINO_MPU // MPU6050 Break Out onboard 3.3V reg 59 //#define CRIUS_AIO_PRO_V1 60 //#define DESQUARED6DOFV2GO // DEsquared V2 with ITG3200 only 61 //#define DESQUARED6DOFV4 // DEsquared V4 with MPU6050 62 //#define LADYBIRD 63 //#define MEGAWAP_V2_STD // available here: http://www.multircshop.com <- confirmed by Alex 64 //#define MEGAWAP_V2_ADV 65 //#define HK_MultiWii_SE_V2 // Hobbyking board with MPU6050 + HMC5883L + BMP085 66 //#define HK_MultiWii_328P // Also labeled "Hobbybro" on the back. ITG3205 + BMA180 + BMP085 + NMC5583L + DSM2 Connector (Spektrum Satellite) 67 //#define RCNet_FC // RCNet FC with MPU6050 and MS561101BA http://www.rcnet.com 68 //#define RCNet_FC_GPS // RCNet FC with MPU6050 + MS561101BA + HMC5883L + UBLOX GPS http://www.rcnet.com 69 //#define FLYDU_ULTRA // MEGA+10DOF+MT3339 FC 70 //#define DIYFLYING_MAGE_V1 // diyflying 10DOF mega board with MPU6050 + HMC5883L + BMP085 http://www.indoor-flying.hk 71 //#define MultiWii_32U4_SE // Hextronik MultiWii_32U4_SE 72 //#define MultiWii_32U4_SE_no_baro // Hextronik MultiWii_32U4_SE without the MS561101BA to free flash-memory for other functions 73 //#define Flyduino9DOF // Flyduino 9DOF IMU MPU6050+HMC5883l 74 //#define Nano_Plane // Multiwii Plane version with tail-front LSM330 sensor http://www.radiosait.ru/en/page_5324.html
- 独立传感器选择
1 /* leave it commented if you already checked a specific board above */ 2 /* I2C gyroscope */ 3 //#define WMP 4 //#define ITG3050 5 //#define ITG3200 6 //#define MPU3050 7 //#define L3G4200D 8 //#define MPU6050 //combo + ACC 9 //#define LSM330 //combo + ACC 10 11 /* I2C accelerometer */ 12 //#define MMA7455 13 //#define ADXL345 14 //#define BMA020 15 //#define BMA180 16 //#define BMA280 17 //#define LIS3LV02 18 //#define LSM303DLx_ACC 19 //#define MMA8451Q 20 21 /* I2C barometer */ 22 //#define BMP085 23 //#define MS561101BA 24 25 /* I2C magnetometer */ 26 //#define HMC5843 27 //#define HMC5883 28 //#define AK8975 29 //#define MAG3110 30 31 /* Sonar */ // for visualization purpose currently - no control code behind 32 //#define SRF02 // use the Devantech SRF i2c sensors 33 //#define SRF08 34 //#define SRF10 35 //#define SRF23 36 37 /* ADC accelerometer */ // for 5DOF from sparkfun, uses analog PIN A1/A2/A3 38 //#define ADCACC 39 40 /* enforce your individual sensor orientation - even overrides board specific defaults */ 41 //#define FORCE_ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = Y; imu.accADC[PITCH] = -X; imu.accADC[YAW] = Z;} 42 //#define FORCE_GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = -Y; imu.gyroADC[PITCH] = X; imu.gyroADC[YAW] = Z;} 43 //#define FORCE_MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = Z;} 44 45 /* Board orientation shift */ 46 /* If you have frame designed only for + mode and you cannot rotate FC phisycally for flying in X mode (or vice versa) 47 * you can use one of of this options for virtual sensors rotation by 45 deegres, then set type of multicopter according to flight mode. 48 * Check motors order and directions of motors rotation for matching with new front point! Uncomment only one option! */ 49 //#define SENSORS_TILT_45DEG_RIGHT // rotate the FRONT 45 degres clockwise 50 //#define SENSORS_TILT_45DEG_LEFT // rotate the FRONT 45 degres counterclockwise
- PID控制器类型
1 /* choose one of the alternate PID control algorithms 2 * 1 = evolved oldschool algorithm (similar to v2.2) 3 * 2 = new experimental algorithm from Alex Khoroshko - unsupported - http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671&start=10#p37387 4 * */ 5 #define PID_CONTROLLER 1
- Arduino Pro Mini开启aux2
1 /* possibility to use PIN8 or PIN12 as the AUX2 RC input (only one, not both) 2 it deactivates in this case the POWER PIN (pin 12) or the BUZZER PIN (pin 8) */ 3 #define RCAUXPIN8 4 //#define RCAUXPIN12
- 低通滤波器频率设置
1 /**************************************************************************************/ 2 /******** Gyro filters ********************/ 3 /**************************************************************************************/ 4 5 /********************* Lowpass filter for some gyros ****************************/ 6 /* ITG3200 & ITG3205 Low pass filter setting. In case you cannot eliminate all vibrations to the Gyro, you can try 7 to decrease the LPF frequency, only one step per try. As soon as twitching gone, stick with that setting. 8 It will not help on feedback wobbles, so change only when copter is randomly twiching and all dampening and 9 balancing options ran out. Uncomment only one option! 10 IMPORTANT! Change low pass filter setting changes PID behaviour, so retune your PID's after changing LPF. 11 available for ITG3050, ITG3200, MPU3050, MPU6050*/ 12 //#define GYRO_LPF_256HZ // This is the default setting, no need to uncomment, just for reference 13 //#define GYRO_LPF_188HZ 14 //#define GYRO_LPF_98HZ 15 //#define GYRO_LPF_42HZ 16 #define GYRO_LPF_20HZ18 //#define GYRO_LPF_10HZ 19 //#define GYRO_LPF_5HZ // Use this only in extreme cases, rather change motors and/or props -- setting not available on ITG3200
- 无头模式
1 /*** HEADFREE : the copter can be controled by an absolute stick orientation, whatever the yaw orientation ***/ 2 #define HEADFREE
- 防炸鸡
1 /******** Failsafe settings ********************/ 2 /* Failsafe check pulses on four main control channels CH1-CH4. If the pulse is missing or bellow 985us (on any of these four channels) 3 the failsafe procedure is initiated. After FAILSAFE_DELAY time from failsafe detection, the level mode is on (if ACC is avaliable), 4 PITCH, ROLL and YAW is centered and THROTTLE is set to FAILSAFE_THROTTLE value. You must set this value to descending about 1m/s or so 5 for best results. This value is depended from your configuration, AUW and some other params. Next, after FAILSAFE_OFF_DELAY the copter is disarmed, 6 and motors is stopped. If RC pulse coming back before reached FAILSAFE_OFF_DELAY time, after the small quard time the RC control is returned to normal. */ 7 //#define FAILSAFE // uncomment to activate the failsafe function 8 #define FAILSAFE_DELAY 10 // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example 9 #define FAILSAFE_OFF_DELAY 200 // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example 10 #define FAILSAFE_THROTTLE (MINTHROTTLE + 200) // (*) Throttle level used for landing - may be relative to MINTHROTTLE - as in this case 11 12 #define FAILSAFE_DETECT_TRESHOLD 985
- LED灯
/***************** DFRobot LED RING *********************************/ /* I2C DFRobot LED RING communication */ //#define LED_RING
- LED闪烁方式
1 /******************************** LED FLASHER ***********************************/ 2 //#define LED_FLASHER 3 //#define LED_FLASHER_DDR DDRB 4 //#define LED_FLASHER_PORT PORTB 5 //#define LED_FLASHER_BIT PORTB4 6 //#define LED_FLASHER_INVERT 7 //#define LED_FLASHER_SEQUENCE 0b00000000 // leds OFF 8 //#define LED_FLASHER_SEQUENCE_ARMED 0b00000101 // create double flashes 9 //#define LED_FLASHER_SEQUENCE_MAX 0b11111111 // full illumination 10 //#define LED_FLASHER_SEQUENCE_LOW 0b00000000 // no illumination
- 着陆灯
1 /******************************* Landing lights *********************************/ 2 /* Landing lights 3 Use an output pin to control landing lights. 4 They can be switched automatically when used in conjunction 5 with altitude data from a sonar unit. */ 6 //#define LANDING_LIGHTS_DDR DDRC 7 //#define LANDING_LIGHTS_PORT PORTC 8 //#define LANDING_LIGHTS_BIT PORTC0 9 //#define LANDING_LIGHTS_INVERT 10 11 /* altitude above ground (in cm) as reported by sonar */ 12 //#define LANDING_LIGHTS_AUTO_ALTITUDE 50 13 14 /* adopt the flasher pattern for landing light LEDs */ 15 //#define LANDING_LIGHTS_ADOPT_LED_FLASHER_PATTERN
- GPS波特率
#define GPS_BAUD 115200 // GPS_BAUD will override SERIALx_COM_SPEED for the selected port
- 开启I2CGPS(用于双328p模式的导航板)
#define I2C_GPS
- I2C GPS导航板上的声呐
#define I2C_GPS_SONAR
- 磁偏角
#define MAG_DECLINATION 3.7f
- GPS HOME最小速度
1 // minimum speed when approach waypoint 2 #define NAV_SPEED_MIN 100 // cm/sec //(**)
- GPS HOME最大速度
// maximum speed to reach between waypoints #define NAV_SPEED_MAX 400 // cm/sec //(**)
- 着陆速度
//This governs the descent speed during landing. 100 is equals approc 50cm/sec #define LAND_SPEED 40