AP_Compass: remove unused variables from AP_Compass_RM3100.h
This commit is contained in:
parent
ff9460d835
commit
97f2d946ab
@ -51,8 +51,6 @@ private:
|
||||
void timer();
|
||||
|
||||
uint8_t compass_instance;
|
||||
Vector3f accum;
|
||||
uint16_t accum_count;
|
||||
bool force_external;
|
||||
enum Rotation rotation;
|
||||
float _scaler = 1.0;
|
||||
|
Loading…
Reference in New Issue
Block a user