Skip to content

Commit

Permalink
Configure config.h for a quad copter
Browse files Browse the repository at this point in the history
  • Loading branch information
cedlecomte committed Jul 2, 2014
1 parent 4853caa commit 9a53223
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions config.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
//#define BI
//#define TRI
//#define QUADP
//#define QUADX
#define QUADX
//#define Y4
//#define Y6
//#define HEX6
Expand Down Expand Up @@ -88,7 +88,7 @@
please submit any correction to this list.
Note from Alex: I only own some boards, for other boards, I'm not sure, the info was gathered via rc forums, be cautious */
//#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 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
Expand Down Expand Up @@ -464,7 +464,7 @@
/* This is the speed of the serial interfaces */
#define SERIAL0_COM_SPEED 115200
#define SERIAL1_COM_SPEED 115200
#define SERIAL2_COM_SPEED 115200
#define SERIAL2_COM_SPEED 57600
#define SERIAL3_COM_SPEED 115200

/* interleaving delay in micro seconds between 2 readings WMP/NK in a WMP+NK config
Expand Down Expand Up @@ -638,7 +638,7 @@
in NMEA mode the GPS must be configured to output GGA and RMC NMEA sentences (which is generally the default conf for most GPS devices)
at least 5Hz update rate. uncomment the first line to select the GPS serial port of the arduino */

//#define GPS_SERIAL 2 // should be 2 for flyduino v2. It's the serial port number on arduino MEGA
#define GPS_SERIAL 2 // should be 2 for flyduino v2. It's the serial port number on arduino MEGA
//#define GPS_PROMINI_SERIAL // Will Autosense if GPS is connected when ardu boots.

// avoid using 115200 baud because with 16MHz arduino the 115200 baudrate have more than 2% speed error (57600 have 0.8% error)
Expand All @@ -651,7 +651,7 @@
With UBLOX and MTK_BINARY you don't have to use GPS_FILTERING in multiwii code !!! */


//#define NMEA
#define NMEA
//#define UBLOX
//#define MTK_BINARY16
//#define MTK_BINARY19
Expand Down Expand Up @@ -690,7 +690,7 @@
Convert the degree+minutes into decimal degree by ==> degree+minutes*(1/60)
Note the sign on declination it could be negative or positive (WEST or EAST) */
//#define MAG_DECLINATION 3.96f //For Budapest Hungary.
#define MAG_DECLINATION 0.0f //(**)
#define MAG_DECLINATION -14.7f //(**)

#define GPS_LEAD_FILTER // Adds a forward predictive filterig to compensate gps lag. Code based on Jason Short's lead filter implementation

Expand Down

0 comments on commit 9a53223

Please sign in to comment.