ardupilot/libraries/AP_Compass/Compass.h
Víctor Mayoral Vilches 13f0aa5ecd AP_Compass: Separate common code into backend
_copy_to_frontend function takes care of abstracting
this code from the driver. For now the function takes
care of the offset and rotation that is common.
2015-03-13 18:46:15 +11:00

350 lines
12 KiB
C++

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef Compass_h
#define Compass_h
#include <inttypes.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
#include <AP_HAL.h>
#include "AP_Compass_Backend.h"
extern const AP_HAL::HAL& hal;
// compass product id
#define AP_COMPASS_TYPE_UNKNOWN 0x00
#define AP_COMPASS_TYPE_HIL 0x01
#define AP_COMPASS_TYPE_HMC5843 0x02
#define AP_COMPASS_TYPE_HMC5883L 0x03
#define AP_COMPASS_TYPE_PX4 0x04
#define AP_COMPASS_TYPE_VRBRAIN 0x05
#define AP_COMPASS_TYPE_AK8963_MPU9250 0x06
// motor compensation types (for use with motor_comp_enabled)
#define AP_COMPASS_MOT_COMP_DISABLED 0x00
#define AP_COMPASS_MOT_COMP_THROTTLE 0x01
#define AP_COMPASS_MOT_COMP_CURRENT 0x02
// setup default mag orientation for each board type
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
# define MAG_BOARD_ORIENTATION ROTATION_ROLL_180
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
# define MAG_BOARD_ORIENTATION ROTATION_NONE
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
# define MAG_BOARD_ORIENTATION ROTATION_NONE
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
# define MAG_BOARD_ORIENTATION ROTATION_NONE
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
# define MAG_BOARD_ORIENTATION ROTATION_NONE
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
# define MAG_BOARD_ORIENTATION ROTATION_NONE
#else
# define MAG_BOARD_ORIENTATION ROTATION_NONE
#endif
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
# define MAG_BOARD_ORIENTATION ROTATION_NONE
#else
# error "You must define a default compass orientation for this board"
#endif
/**
maximum number of compass instances available on this platform. If more
than 1 then redundent sensors may be available
*/
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#define COMPASS_MAX_INSTANCES 3
#define COMPASS_MAX_BACKEND 3
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#define COMPASS_MAX_INSTANCES 2
#define COMPASS_MAX_BACKEND 2
#else
#define COMPASS_MAX_INSTANCES 1
#define COMPASS_MAX_BACKEND 1
#endif
class Compass
{
friend class AP_Compass_Backend;
friend class AP_Compass_HIL;
friend class AP_Compass_VRBRAIN;
friend class AP_Compass_PX4;
friend class AP_Compass_AK8963;
friend class AP_Compass_HMC5843;
public:
uint32_t last_update; ///< micros() time of last update
int16_t product_id; /// product id
/// Constructor
///
Compass();
/// Initialize the compass device.
///
/// @returns True if the compass was initialized OK, false if it was not
/// found or is not functioning.
///
bool init();
/// Read the compass and update the mag_ variables.
///
bool read();
/// use spare CPU cycles to accumulate values from the compass if
/// possible (this method should also be implemented in the backends)
void accumulate();
/// Register a new compas driver, allocating an instance number
///
/// @return number of compass instances
uint8_t register_compass(void);
// load backend drivers
void _add_backend(AP_Compass_Backend *(detect)(Compass &));
void _detect_backends(void);
/// Calculate the tilt-compensated heading_ variables.
///
/// @param dcm_matrix The current orientation rotation matrix
///
/// @returns heading in radians
///
float calculate_heading(const Matrix3f &dcm_matrix) const;
/// Sets offset x/y/z values.
///
/// @param i compass instance
/// @param offsets Offsets to the raw mag_ values.
///
void set_offsets(uint8_t i, const Vector3f &offsets);
/// Sets and saves the compass offset x/y/z values.
///
/// @param i compass instance
/// @param offsets Offsets to the raw mag_ values.
///
void set_and_save_offsets(uint8_t i, const Vector3f &offsets);
/// Saves the current offset x/y/z values for one or all compasses
///
/// @param i compass instance
///
/// This should be invoked periodically to save the offset values maintained by
/// ::learn_offsets.
///
void save_offsets(uint8_t i);
void save_offsets(void);
// return the number of compass instances
uint8_t get_count(void) const { return _compass_count; }
/// Return the current field as a Vector3f
const Vector3f &get_field(uint8_t i) const { return _field[i]; }
const Vector3f &get_field(void) const { return get_field(get_primary()); }
/// Return the health of a compass
bool healthy(uint8_t i) const { return _healthy[i]; }
bool healthy(void) const { return healthy(get_primary()); }
/// set the current field as a Vector3f
void set_field(const Vector3f &field) { _field[0] = field; }
/// Returns the current offset values
///
/// @returns The current compass offsets.
///
const Vector3f &get_offsets(uint8_t i) const { return _offset[i]; }
const Vector3f &get_offsets(void) const { return get_offsets(get_primary()); }
/// Sets the initial location used to get declination
///
/// @param latitude GPS Latitude.
/// @param longitude GPS Longitude.
///
void set_initial_location(int32_t latitude, int32_t longitude);
/// Program new offset values.
///
/// @param i compass instance
/// @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_and_save_offsets(uint8_t i, int x, int y, int z) {
set_and_save_offsets(i, Vector3f(x, y, z));
}
// learn offsets accessor
bool learn_offsets_enabled() const { return _learn; }
/// Perform automatic offset updates
///
void learn_offsets(void);
/// return true if the compass should be used for yaw calculations
bool use_for_yaw(uint8_t i) const;
bool use_for_yaw(void) const;
/// Sets the local magnetic field declination.
///
/// @param radians Local field declination.
/// @param save_to_eeprom true to save to eeprom (false saves only to memory)
///
void set_declination(float radians, bool save_to_eeprom = true);
float get_declination() const;
// set overall board orientation
void set_board_orientation(enum Rotation orientation) {
_board_orientation = orientation;
}
enum Rotation get_board_orientation() { return _board_orientation;}
AP_Int8 get_orientation() { return _orientation[0];}
AP_Int8 get_orientation(uint8_t instance) { return _orientation[instance];}
/// Set the motor compensation type
///
/// @param comp_type 0 = disabled, 1 = enabled use throttle, 2 = enabled use current
///
void motor_compensation_type(const uint8_t comp_type) {
if (_motor_comp_type <= AP_COMPASS_MOT_COMP_CURRENT && _motor_comp_type != (int8_t)comp_type) {
_motor_comp_type = (int8_t)comp_type;
_thr_or_curr = 0; // set current current or throttle to zero
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
set_motor_compensation(i, Vector3f(0,0,0)); // clear out invalid compensation vectors
}
}
}
/// get the motor compensation value.
uint8_t motor_compensation_type() const {
return _motor_comp_type;
}
/// Set the motor compensation factor x/y/z values.
///
/// @param i instance of compass
/// @param offsets Offsets multiplied by the throttle value and added to the raw mag_ values.
///
void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor);
/// get motor compensation factors as a vector
const Vector3f& get_motor_compensation(uint8_t i) const { return _motor_compensation[i]; }
const Vector3f& get_motor_compensation(void) const { return get_motor_compensation(get_primary()); }
/// Saves the current motor compensation x/y/z values.
///
/// This should be invoked periodically to save the offset values calculated by the motor compensation auto learning
///
void save_motor_compensation();
/// Returns the current motor compensation offset values
///
/// @returns The current compass offsets.
///
const Vector3f &get_motor_offsets(uint8_t i) const { return _motor_offset[i]; }
const Vector3f &get_motor_offsets(void) const { return get_motor_offsets(get_primary()); }
/// Set the throttle as a percentage from 0.0 to 1.0
/// @param thr_pct throttle expressed as a percentage from 0 to 1.0
void set_throttle(float thr_pct) {
if(_motor_comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
_thr_or_curr = thr_pct;
}
}
/// Set the current used by system in amps
/// @param amps current flowing to the motors expressed in amps
void set_current(float amps) {
if(_motor_comp_type == AP_COMPASS_MOT_COMP_CURRENT) {
_thr_or_curr = amps;
}
}
/// Returns True if the compasses have been configured (i.e. offsets saved)
///
/// @returns True if compass has been configured
///
bool configured(uint8_t i);
bool configured(void);
/// Returns the instance of the primary compass
///
/// @returns the instance number of the primary compass
///
uint8_t get_primary(void) const { return 0; }
void apply_corrections(Vector3f &mag, uint8_t i);
// HIL methods
void setHIL(float roll, float pitch, float yaw);
void setHIL(const Vector3f &mag);
const Vector3f& getHIL() const;
void _setup_earth_field();
Vector3f _hil_mag;
static const struct AP_Param::GroupInfo var_info[];
// settable parameters
AP_Int8 _learn; ///<enable calibration learning
/// Return the product ID
///
/// @return the product ID
///
// int16_t product_id(void) const { return product_id; }
AP_Int8 _external[COMPASS_MAX_INSTANCES]; ///<compass is external
bool _healthy[COMPASS_MAX_INSTANCES];
// board orientation from AHRS
enum Rotation _board_orientation;
AP_Int8 _orientation[COMPASS_MAX_INSTANCES];
AP_Vector3f _offset[COMPASS_MAX_INSTANCES];
#if COMPASS_MAX_INSTANCES > 1
AP_Int8 _primary; ///primary instance
AP_Int32 _dev_id[COMPASS_MAX_INSTANCES]; // device id detected at init. saved to eeprom when offsets are saved allowing ram & eeprom values to be compared as consistency check
#endif
protected:
// backend objects
AP_Compass_Backend *_backends[COMPASS_MAX_INSTANCES];
// number of compasses
uint8_t _compass_count;
uint8_t _backend_count;
AP_Float _declination;
AP_Int8 _use_for_yaw[COMPASS_MAX_INSTANCES];///<enable use for yaw calculation
AP_Int8 _auto_declination; ///<enable automatic declination code
bool _null_init_done; ///< first-time-around flag used by offset nulling
///< used by offset correction
static const uint8_t _mag_history_size = 20;
uint8_t _mag_history_index[COMPASS_MAX_INSTANCES];
Vector3i _mag_history[COMPASS_MAX_INSTANCES][_mag_history_size];
// motor compensation
AP_Int8 _motor_comp_type; // 0 = disabled, 1 = enabled for throttle, 2 = enabled for current
AP_Vector3f _motor_compensation[COMPASS_MAX_INSTANCES]; // factors multiplied by throttle and added to compass outputs
Vector3f _motor_offset[COMPASS_MAX_INSTANCES]; // latest compensation added to compass
float _thr_or_curr; // throttle expressed as a percentage from 0 ~ 1.0 or current expressed in amps
// HIL variables
Vector3f _Bearth;
float _last_declination;
private:
Vector3f _field[COMPASS_MAX_INSTANCES]; ///< magnetic field strength
};
#include "AP_Compass_Backend.h"
#include "AP_Compass_HMC5843.h"
#include "AP_Compass_HIL.h"
#include "AP_Compass_AK8963.h"
#include "AP_Compass_PX4.h"
#endif