ardupilot/libraries/AP_Compass/Compass.h
jasonshort 729cf47b3c needs some help
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1001 f9c3cf11-9bcb-44bc-f272-b75c42450872
2010-12-02 05:54:02 +00:00

26 lines
540 B
C++

#ifndef Compass_h
#define Compass_h
#include <inttypes.h>
#include <AP_Math.h>
class Compass
{
public:
int mag_x;
int mag_y;
int mag_z;
float heading;
float heading_x;
float heading_y;
unsigned long last_update;
virtual bool init(int initialise_wire_lib = 1);
virtual void read();
virtual void calculate(float roll, float pitch);
virtual void set_orientation(const Matrix3f &rotation_matrix);
virtual void set_offsets(int x, int y, int z);
virtual void set_declination(float radians);
};
#endif