From a8b995ae1a38e6cae1682ea7f5ccfa1bf0060d34 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Mon, 30 Aug 2010 00:16:35 +0000 Subject: [PATCH] fixed text encoding git-svn-id: https://arducopter.googlecode.com/svn/trunk@352 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- .../APM_Compass_test/APM_Compass_test.pde | 80 +++++++++---------- 1 file changed, 40 insertions(+), 40 deletions(-) diff --git a/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde b/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde index a82aeba9d3..83f05e82a8 100644 --- a/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde +++ b/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde @@ -1,41 +1,41 @@ -/* - Example of APM_Compass library (HMC5843 sensor). - Code by Jordi Muñoz and Jose Julio. DIYDrones.com -*/ - -#include -#include // Compass Library - -#define ToDeg(x) (x*57.2957795131) // *180/pi - -unsigned long timer; - -void setup() -{ - APM_Compass.Init(); // Initialization - Serial.begin(57600); - Serial.println("Compass library test (HMC5843)"); - delay(1000); - timer = millis(); -} - -void loop() -{ - float tmp; - - if((millis()- timer) > 100) - { - timer = millis(); - APM_Compass.Read(); - APM_Compass.Calculate(0,0); // roll = 0, pitch = 0 for this example - Serial.print("Heading:"); - Serial.print(ToDeg(APM_Compass.Heading)); - Serial.print(" ("); - Serial.print(APM_Compass.Mag_X); - Serial.print(","); - Serial.print(APM_Compass.Mag_Y); - Serial.print(","); - Serial.print(APM_Compass.Mag_Z); - Serial.println(); - } +/* + Example of APM_Compass library (HMC5843 sensor). + Code by Jordi MuÃ’oz and Jose Julio. DIYDrones.com +*/ + +#include +#include // Compass Library + +#define ToDeg(x) (x*57.2957795131) // *180/pi + +unsigned long timer; + +void setup() +{ + APM_Compass.Init(); // Initialization + Serial.begin(38400); + Serial.println("Compass library test (HMC5843)"); + delay(1000); + timer = millis(); +} + +void loop() +{ + float tmp; + + if((millis()- timer) > 100) + { + timer = millis(); + APM_Compass.Read(); + APM_Compass.Calculate(0,0); // roll = 0, pitch = 0 for this example + Serial.print("Heading:"); + Serial.print(ToDeg(APM_Compass.Heading)); + Serial.print(" ("); + Serial.print(APM_Compass.Mag_X); + Serial.print(","); + Serial.print(APM_Compass.Mag_Y); + Serial.print(","); + Serial.print(APM_Compass.Mag_Z); + Serial.println(" )"); + } } \ No newline at end of file