removing DONT_USE flags and minor changes

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1056 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jphelirc 2010-12-06 14:56:55 +00:00
parent d13850c941
commit 9b3b5320fc
3 changed files with 6 additions and 4 deletions

View File

@ -57,18 +57,18 @@ TODO:
/* Will be moved in future to AN extension ports */
/* due need to have PWM pins free for sonars and servos */
/*
#define FR_LED 3 // Mega PE4 pin, OUT7
#define RE_LED 2 // Mega PE5 pin, OUT6
#define RI_LED 7 // Mega PH4 pin, OUT5
#define LE_LED 8 // Mega PH5 pin, OUT4
*/
/*
#define FR_LED AN12 // Mega PE4 pin, OUT7
#define RE_LED AN14 // Mega PE5 pin, OUT6
#define RI_LED AN10 // Mega PH4 pin, OUT5
#define LE_LED AN8 // Mega PH5 pin, OUT4
*/
/*************************************************************/

View File

@ -152,13 +152,15 @@
// you need to roll/bank/tilt/yaw/shake etc your ArduCopter. Don't kick like Jani always does :)
#define MAGOFFSET 0,0,0
//#define MAGOFFSET 19.00,-72.00,-79.50
//#define MAGOFFSET -27.50,23.00,81.00
// Declination is a correction factor between North Pole and real magnetic North. This is different on every location
// IF you want to use really accurate headholding and future navigation features, you should update this
// You can check Declination to your location from http://www.magnetic-declination.com/
#define DECLINATION 0.00
//#define DECLINATION 0.61
// And remember result from NOAA website is in form of DEGREES°MINUTES'. Degrees you can use directly but Minutes you need to
// recalculate due they one degree is 60 minutes.. For example Jani's real declination is 0.61, correct way to calculate this is
// 37 / 60 = 0.61 and for Helsinki it would be 7°44' eg 7. and then 44/60 = 0.73 so declination for Helsinki/South Finland would be 7.73

View File