Updated compass library.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@995 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-12-02 05:13:12 +00:00
parent 93206020cb
commit 45ddbbf982
2 changed files with 23 additions and 32 deletions

View File

@ -1,17 +1,7 @@
#ifndef AP_Compass_h
#define AP_Compass_h
#include <Compass.h>
class AP_Compass : public Compass
{
public:
AP_Compass(); // Constructor
void init();
void update();
void calculate(float roll, float pitch);
private:
};
#endif
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
/// @file AP_Compass.h
/// @brief Catch-all header that defines all supported compass classes.
#include "AP_Compass_HMC5843.h"
#include "AP_Compass_HIL.h"

View File

@ -2,24 +2,25 @@
#define Compass_h
#include <inttypes.h>
#include <AP_Math>
#include <AP_Math.h>
class Compass
{
public:
virtual void init();
virtual void update();
virtual void calculate(float roll, float pitch);
Vector3f mag;
int16_t mag_X;
int16_t mag_Y;
int16_t mag_Z;
int32_t ground_course;
int magX;
int magY;
int magZ;
float heading;
float heading_X;
float heading_Y;
float headingX;
float headingY;
unsigned long lastUpdate;
//
virtual bool init(int initialiseWireLib = 1);
virtual void read();
virtual void calculate(float roll, float pitch);
virtual void setOrientation(const Matrix3f &rotationMatrix);
virtual void setOffsets(int x, int y, int z);
virtual void setDeclination(float radians);
};
#endif
#endif