mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
uncrustify libraries/AP_Compass/Compass.h
This commit is contained in:
parent
8f9bb7f92c
commit
cf69da594f
@ -16,116 +16,120 @@
|
|||||||
class Compass
|
class Compass
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
int16_t product_id; /// product id
|
int16_t product_id; /// product id
|
||||||
int16_t mag_x; ///< magnetic field strength along the X axis
|
int16_t mag_x; ///< magnetic field strength along the X axis
|
||||||
int16_t mag_y; ///< magnetic field strength along the Y axis
|
int16_t mag_y; ///< magnetic field strength along the Y axis
|
||||||
int16_t mag_z; ///< magnetic field strength along the Z axis
|
int16_t mag_z; ///< magnetic field strength along the Z axis
|
||||||
uint32_t last_update; ///< micros() time of last update
|
uint32_t last_update; ///< micros() time of last update
|
||||||
bool healthy; ///< true if last read OK
|
bool healthy; ///< true if last read OK
|
||||||
|
|
||||||
/// Constructor
|
/// Constructor
|
||||||
///
|
|
||||||
Compass();
|
|
||||||
|
|
||||||
/// Initialize the compass device.
|
|
||||||
///
|
|
||||||
/// @returns True if the compass was initialized OK, false if it was not
|
|
||||||
/// found or is not functioning.
|
|
||||||
///
|
|
||||||
virtual bool init();
|
|
||||||
|
|
||||||
/// Read the compass and update the mag_ variables.
|
|
||||||
///
|
|
||||||
virtual bool read(void) = 0;
|
|
||||||
|
|
||||||
/// Calculate the tilt-compensated heading_ variables.
|
|
||||||
///
|
|
||||||
/// @param roll The current airframe roll angle.
|
|
||||||
/// @param pitch The current airframe pitch angle.
|
|
||||||
///
|
|
||||||
/// @returns heading in radians
|
|
||||||
///
|
///
|
||||||
virtual float calculate_heading(float roll, float pitch);
|
Compass();
|
||||||
|
|
||||||
/// Calculate the tilt-compensated heading_ variables.
|
/// Initialize the compass device.
|
||||||
///
|
///
|
||||||
/// @param dcm_matrix The current orientation rotation matrix
|
/// @returns True if the compass was initialized OK, false if it was not
|
||||||
|
/// found or is not functioning.
|
||||||
|
///
|
||||||
|
virtual bool init();
|
||||||
|
|
||||||
|
/// Read the compass and update the mag_ variables.
|
||||||
|
///
|
||||||
|
virtual bool read(void) = 0;
|
||||||
|
|
||||||
|
/// Calculate the tilt-compensated heading_ variables.
|
||||||
|
///
|
||||||
|
/// @param roll The current airframe roll angle.
|
||||||
|
/// @param pitch The current airframe pitch angle.
|
||||||
///
|
///
|
||||||
/// @returns heading in radians
|
/// @returns heading in radians
|
||||||
///
|
///
|
||||||
virtual float calculate_heading(const Matrix3f &dcm_matrix);
|
virtual float calculate_heading(float roll, float pitch);
|
||||||
|
|
||||||
/// Set the compass orientation matrix, used to correct for
|
/// Calculate the tilt-compensated heading_ variables.
|
||||||
/// various compass mounting positions.
|
///
|
||||||
///
|
/// @param dcm_matrix The current orientation rotation matrix
|
||||||
/// @param rotation_matrix Rotation matrix to transform magnetometer readings
|
///
|
||||||
/// to the body frame.
|
/// @returns heading in radians
|
||||||
///
|
///
|
||||||
virtual void set_orientation(enum Rotation rotation);
|
virtual float calculate_heading(const Matrix3f &dcm_matrix);
|
||||||
|
|
||||||
/// Sets the compass offset x/y/z values.
|
/// Set the compass orientation matrix, used to correct for
|
||||||
///
|
/// various compass mounting positions.
|
||||||
/// @param offsets Offsets to the raw mag_ values.
|
///
|
||||||
///
|
/// @param rotation_matrix Rotation matrix to transform magnetometer readings
|
||||||
virtual void set_offsets(const Vector3f &offsets);
|
/// to the body frame.
|
||||||
|
///
|
||||||
|
virtual void set_orientation(enum Rotation rotation);
|
||||||
|
|
||||||
/// Saves the current compass offset x/y/z values.
|
/// Sets the compass offset x/y/z values.
|
||||||
///
|
///
|
||||||
/// This should be invoked periodically to save the offset values maintained by
|
/// @param offsets Offsets to the raw mag_ values.
|
||||||
/// ::null_offsets.
|
///
|
||||||
///
|
virtual void set_offsets(const Vector3f &offsets);
|
||||||
virtual void save_offsets();
|
|
||||||
|
|
||||||
/// Returns the current offset values
|
/// Saves the current compass offset x/y/z values.
|
||||||
///
|
///
|
||||||
/// @returns The current compass offsets.
|
/// This should be invoked periodically to save the offset values maintained by
|
||||||
///
|
/// ::null_offsets.
|
||||||
virtual Vector3f &get_offsets();
|
///
|
||||||
|
virtual void save_offsets();
|
||||||
|
|
||||||
/// Sets the initial location used to get declination
|
/// Returns the current offset values
|
||||||
///
|
///
|
||||||
/// @param latitude GPS Latitude.
|
/// @returns The current compass offsets.
|
||||||
/// @param longitude GPS Longitude.
|
///
|
||||||
///
|
virtual Vector3f &get_offsets();
|
||||||
void set_initial_location(int32_t latitude, int32_t longitude);
|
|
||||||
|
|
||||||
/// Program new offset values.
|
/// Sets the initial location used to get declination
|
||||||
///
|
///
|
||||||
/// @param x Offset to the raw mag_x value.
|
/// @param latitude GPS Latitude.
|
||||||
/// @param y Offset to the raw mag_y value.
|
/// @param longitude GPS Longitude.
|
||||||
/// @param z Offset to the raw mag_z value.
|
///
|
||||||
///
|
void set_initial_location(int32_t latitude, int32_t longitude);
|
||||||
void set_offsets(int x, int y, int z) { set_offsets(Vector3f(x, y, z)); }
|
|
||||||
|
|
||||||
/// Perform automatic offset updates
|
/// Program new offset values.
|
||||||
///
|
///
|
||||||
void null_offsets(void);
|
/// @param x Offset to the raw mag_x value.
|
||||||
|
/// @param y Offset to the raw mag_y value.
|
||||||
|
/// @param z Offset to the raw mag_z value.
|
||||||
|
///
|
||||||
|
void set_offsets(int x, int y, int z) {
|
||||||
|
set_offsets(Vector3f(x, y, z));
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Perform automatic offset updates
|
||||||
|
///
|
||||||
|
void null_offsets(void);
|
||||||
|
|
||||||
/// return true if the compass should be used for yaw calculations
|
/// return true if the compass should be used for yaw calculations
|
||||||
bool use_for_yaw(void) { return healthy && _use_for_yaw; }
|
bool use_for_yaw(void) {
|
||||||
|
return healthy && _use_for_yaw;
|
||||||
|
}
|
||||||
|
|
||||||
/// Sets the local magnetic field declination.
|
/// Sets the local magnetic field declination.
|
||||||
///
|
///
|
||||||
/// @param radians Local field declination.
|
/// @param radians Local field declination.
|
||||||
///
|
///
|
||||||
virtual void set_declination(float radians);
|
virtual void set_declination(float radians);
|
||||||
float get_declination();
|
float get_declination();
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
enum Rotation _orientation;
|
enum Rotation _orientation;
|
||||||
AP_Vector3f _offset;
|
AP_Vector3f _offset;
|
||||||
AP_Float _declination;
|
AP_Float _declination;
|
||||||
AP_Int8 _learn; ///<enable calibration learning
|
AP_Int8 _learn; ///<enable calibration learning
|
||||||
AP_Int8 _use_for_yaw; ///<enable use for yaw calculation
|
AP_Int8 _use_for_yaw; ///<enable use for yaw calculation
|
||||||
AP_Int8 _auto_declination; ///<enable automatic declination code
|
AP_Int8 _auto_declination; ///<enable automatic declination code
|
||||||
|
|
||||||
bool _null_init_done; ///< first-time-around flag used by offset nulling
|
bool _null_init_done; ///< first-time-around flag used by offset nulling
|
||||||
|
|
||||||
///< used by offset correction
|
///< used by offset correction
|
||||||
static const uint8_t _mag_history_size = 20;
|
static const uint8_t _mag_history_size = 20;
|
||||||
uint8_t _mag_history_index;
|
uint8_t _mag_history_index;
|
||||||
Vector3i _mag_history[_mag_history_size];
|
Vector3i _mag_history[_mag_history_size];
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user