mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Compass: remove trailing whitespaces in header
This commit is contained in:
parent
cb8355c315
commit
b3d26c5988
@ -17,7 +17,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
uint8_t _num_sensors;
|
uint8_t _num_sensors;
|
||||||
|
|
||||||
uint8_t _instance[COMPASS_MAX_INSTANCES];
|
uint8_t _instance[COMPASS_MAX_INSTANCES];
|
||||||
int _mag_fd[COMPASS_MAX_INSTANCES];
|
int _mag_fd[COMPASS_MAX_INSTANCES];
|
||||||
Vector3f _sum[COMPASS_MAX_INSTANCES];
|
Vector3f _sum[COMPASS_MAX_INSTANCES];
|
||||||
|
@ -18,7 +18,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
void timer_update(void);
|
void timer_update(void);
|
||||||
|
|
||||||
uint8_t instance;
|
uint8_t instance;
|
||||||
Vector3f sum;
|
Vector3f sum;
|
||||||
uint32_t count;
|
uint32_t count;
|
||||||
|
@ -70,7 +70,7 @@ public:
|
|||||||
|
|
||||||
/// Read the compass and update the mag_ variables.
|
/// Read the compass and update the mag_ variables.
|
||||||
///
|
///
|
||||||
bool read();
|
bool read();
|
||||||
|
|
||||||
/// use spare CPU cycles to accumulate values from the compass if
|
/// use spare CPU cycles to accumulate values from the compass if
|
||||||
/// possible (this method should also be implemented in the backends)
|
/// possible (this method should also be implemented in the backends)
|
||||||
@ -322,7 +322,7 @@ private:
|
|||||||
|
|
||||||
//keep track of number of calibration reports sent
|
//keep track of number of calibration reports sent
|
||||||
uint8_t _reports_sent[COMPASS_MAX_INSTANCES];
|
uint8_t _reports_sent[COMPASS_MAX_INSTANCES];
|
||||||
|
|
||||||
//autoreboot after compass calibration
|
//autoreboot after compass calibration
|
||||||
bool _compass_cal_autoreboot;
|
bool _compass_cal_autoreboot;
|
||||||
bool _cal_complete_requires_reboot;
|
bool _cal_complete_requires_reboot;
|
||||||
@ -342,16 +342,16 @@ private:
|
|||||||
enum Rotation _board_orientation;
|
enum Rotation _board_orientation;
|
||||||
|
|
||||||
// primary instance
|
// primary instance
|
||||||
AP_Int8 _primary;
|
AP_Int8 _primary;
|
||||||
|
|
||||||
// declination in radians
|
// declination in radians
|
||||||
AP_Float _declination;
|
AP_Float _declination;
|
||||||
|
|
||||||
// enable automatic declination code
|
// enable automatic declination code
|
||||||
AP_Int8 _auto_declination;
|
AP_Int8 _auto_declination;
|
||||||
|
|
||||||
// first-time-around flag used by offset nulling
|
// first-time-around flag used by offset nulling
|
||||||
bool _null_init_done;
|
bool _null_init_done;
|
||||||
|
|
||||||
// used by offset correction
|
// used by offset correction
|
||||||
static const uint8_t _mag_history_size = 20;
|
static const uint8_t _mag_history_size = 20;
|
||||||
|
Loading…
Reference in New Issue
Block a user