Pure virtual classes should declare pure virtual member functions as 0, rather than having the linker go looking for implementations elesewhere. This lets the compiler generate better error messages when a subclass fails to implement one or more required functions.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1339 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok 2010-12-28 23:31:58 +00:00
parent 6f4e63e8b3
commit eb81becdb6

View File

@ -15,11 +15,11 @@ class Compass
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);
virtual bool init(int initialise_wire_lib = 1) = 0;
virtual void read() = 0;
virtual void calculate(float roll, float pitch) = 0;
virtual void set_orientation(const Matrix3f &rotation_matrix) = 0;
virtual void set_offsets(int x, int y, int z) = 0;
virtual void set_declination(float radians) = 0;
};
#endif