HMC5843L Compass Chip simple programing question

I have my compass chip with the below code, what happens is when I turn the ship counterclockwise it goes 360 then 359 ,358so on till about 270 then it goes back up to 360

how can I modify the code below to make it go from 0-360 ?

#include <Wire.h>
double res = 0;
void setup()
{
 Wire.begin();
 Serial.begin(9600);
 initHMC5843();
 delay(100);
}
void loop()
{
 readxyz();
}
void initHMC5843()
{
   delay(5);
   Wire.beginTransmission(0x1E);// 7 bits address
   Wire.send(0x02);
   Wire.send(0x00); // continues reading
   Wire.endTransmission();
}

void readxyz()
{
   Wire.beginTransmission(0x1E);
   Wire.send(0x03);
   Wire.endTransmission();
   delay(5);
   Wire.requestFrom(0x1E, 6);
   if(6 <= Wire.available())
   {
       int x,y,z;
       x = Wire.receive() << 8;
       x |= Wire.receive();
       y = Wire.receive() << 8;
       y |= Wire.receive();
       z = Wire.receive() << 8;
       z |= Wire.receive();
       if(x>0)
       {
          res = map(x, 0, 246, 0, 90);
       }
       else if(x<0)
       {
         if(x!=0)
         {
           res = abs(x);
           res = map(res,0,255,90,0);
           res = 270+res;
         }
         else
          res = 0;
       }
       Serial.println(res);
   }
}

The specs that I found for that chip say that it returns a value from -2048 to +2047 inclusive. If 0 is zero degrees then I would replace this:

       if(x>0)
       {
          res = map(x, 0, 246, 0, 90);
       }
       else if(x<0)
       {
         if(x!=0)
         {
           res = abs(x);
           res = map(res,0,255,90,0);
           res = 270+res;
         }
         else
          res = 0;
       }

with this:

  if(x >= 0)res = map(x,0,2047,0,180);
  else      res = map(x,-1,-2048,360,180);

Pete
P.S. the map function returns an integer so you might as well declare res to be an integer as well.

how would I incorporate the y axis to return a direction (in degrees)?
with just the x I find it goes from 0 to 270 and back

Do you have a spec sheet for the HMC5843L? It would also help if you could point to some code that works - i.e. code that reads the compass and returns a heading in degrees. I can only find the HMC5843 online and it doesn't seem to work quite the same (or your setup code is wrong).
Also, the values returned by the compass for each axis may not be directions, but a measurement of the magnetic field in which case you have to calibrate your program to what the chip returns.

Pete

ok never mind I got it working

OK, how about enlightening me as to what you did to fix it. It might help others in the future too.

Pete

whether apparently working or not, the device is a magnetometer and requires calibration to relate field to direction.
the datasheet is here:http://www.sparkfun.com/datasheets/Sensors/Magneto/HMC5843.pdf

code for compass (I needed A compass for my robot so i can turn so any degrees before I had it turning for a certain amount of time)
for anyone interested in how to make the robot turn put a loop and turn the robot till the heading is 90 degrees more or less

#define HMC5883_WriteAddress 0x1E //  i.e 0x3C >> 1
#define HMC5883_ModeRegisterAddress 0x02
#define HMC5883_ContinuousModeCommand 0x00
#define HMC5883_DataOutputXMSBAddress  0x03
 
int regb=0x01;
int regbdata=0x40;
 #include <Wire.h>
int outputData[6];
 
void setup()
{ 
    Serial.begin(9600);
    Wire.begin();       //Initiate the Wire library and join the I2C bus as a master
 
}
 
void loop() {
 
    int i,x,y,z;
    double angle;
 
    Wire.beginTransmission(HMC5883_WriteAddress);
    Wire.send(regb);
    Wire.send(regbdata);
    Wire.endTransmission();
 
    delay(1000);
    Wire.beginTransmission(HMC5883_WriteAddress); //Initiate a transmission with HMC5883 (Write address).
    Wire.send(HMC5883_ModeRegisterAddress);       //Place the Mode Register Address in send-buffer.
    Wire.send(HMC5883_ContinuousModeCommand);     //Place the command for Continuous operation Mode in send-buffer.
    Wire.endTransmission();                       //Send the send-buffer to HMC5883 and end the I2C transmission.
    delay(100);
 
 
    Wire.beginTransmission(HMC5883_WriteAddress);  //Initiate a transmission with HMC5883 (Write address).
    Wire.requestFrom(HMC5883_WriteAddress,6);      //Request 6 bytes of data from the address specified.
 
    delay(100);
 
 
    //Read the value of magnetic components X,Y and Z
 
    if(6 <= Wire.available()) // If the number of bytes available for reading be <=6.
    {
        for(i=0;i<6;i++)
        {
            outputData[i]=Wire.receive();  //Store the data in outputData buffer
        }
    }
 
    x=outputData[0] << 8 | outputData[1]; //Combine MSB and LSB of X Data output register
    z=outputData[2] << 8 | outputData[3]; //Combine MSB and LSB of Z Data output register
    y=outputData[4] << 8 | outputData[5]; //Combine MSB and LSB of Y Data output register
 
 
    angle= atan2((double)y,(double)x) * (180 / 3.14159265) + 180; // angle in degrees
 
    /*
 
  Refer the following application note for heading calculation.
  http://www.ssec.honeywell.com/magnetic/datasheets/lowcost.pdf 
  ----------------------------------------------------------------------------------------
  atan2(y, x) is the angle in radians between the positive x-axis of a plane and the point
  given by the coordinates (x, y) on it.
  ----------------------------------------------------------------------------------------
 
  This sketch does not utilize the magnetic component Z as tilt compensation can not be done without an Accelerometer
 
  ----------------->y
  |
  |
  |
  |
  |
  |
 \/
  x
 
 
 
     N
 NW  |  NE
     | 
W----------E
     |
 SW  |  SE
     S
 
 */
 
 
    //Print the approximate direction
 
    Serial.print("You are heading ");
    if((angle < 22.5) || (angle > 337.5 ))
        Serial.print("South  ");
    if((angle > 22.5) && (angle < 67.5 ))
        Serial.print("South-West  ");
    if((angle > 67.5) && (angle < 112.5 ))
        Serial.print("West  ");
    if((angle > 112.5) && (angle < 157.5 ))
        Serial.print("North-West  ");
    if((angle > 157.5) && (angle < 202.5 ))
        Serial.print("North  ");
    if((angle > 202.5) && (angle < 247.5 ))
        Serial.print("NorthEast  ");
    if((angle > 247.5) && (angle < 292.5 ))
        Serial.print("East  ");
    if((angle > 292.5) && (angle < 337.5 ))
        Serial.print("SouthEast  ");
 

/*    if((0 < angle) && (angle < 180) ) //////I got rid of this to make it 0-360 instead of 0-180 then to 0 again
    {
        angle=angle;
    }
    else
    {
        angle=360-angle;
    }*/
    Serial.print(angle,2);
    Serial.println(" Deg");
    delay(100);
}