mirror of https://github.com/ArduPilot/ardupilot
Compass: get_primary method made public
This commit is contained in:
parent
1f579563e6
commit
d291594d7c
|
@ -128,11 +128,11 @@ public:
|
||||||
|
|
||||||
/// Return the current field as a Vector3f
|
/// Return the current field as a Vector3f
|
||||||
const Vector3f &get_field(uint8_t i) const { return _field[i]; }
|
const Vector3f &get_field(uint8_t i) const { return _field[i]; }
|
||||||
const Vector3f &get_field(void) const { return get_field(_get_primary()); }
|
const Vector3f &get_field(void) const { return get_field(get_primary()); }
|
||||||
|
|
||||||
/// Return the health of a compass
|
/// Return the health of a compass
|
||||||
bool healthy(uint8_t i) const { return _healthy[i]; }
|
bool healthy(uint8_t i) const { return _healthy[i]; }
|
||||||
bool healthy(void) const { return healthy(_get_primary()); }
|
bool healthy(void) const { return healthy(get_primary()); }
|
||||||
|
|
||||||
/// set the current field as a Vector3f
|
/// set the current field as a Vector3f
|
||||||
void set_field(const Vector3f &field) { _field[0] = field; }
|
void set_field(const Vector3f &field) { _field[0] = field; }
|
||||||
|
@ -142,7 +142,7 @@ public:
|
||||||
/// @returns The current compass offsets.
|
/// @returns The current compass offsets.
|
||||||
///
|
///
|
||||||
const Vector3f &get_offsets(uint8_t i) const { return _offset[i]; }
|
const Vector3f &get_offsets(uint8_t i) const { return _offset[i]; }
|
||||||
const Vector3f &get_offsets(void) const { return get_offsets(_get_primary()); }
|
const Vector3f &get_offsets(void) const { return get_offsets(get_primary()); }
|
||||||
|
|
||||||
/// Sets the initial location used to get declination
|
/// Sets the initial location used to get declination
|
||||||
///
|
///
|
||||||
|
@ -215,7 +215,7 @@ public:
|
||||||
|
|
||||||
/// get motor compensation factors as a vector
|
/// 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(uint8_t i) const { return _motor_compensation[i]; }
|
||||||
const Vector3f& get_motor_compensation(void) const { return get_motor_compensation(_get_primary()); }
|
const Vector3f& get_motor_compensation(void) const { return get_motor_compensation(get_primary()); }
|
||||||
|
|
||||||
/// Saves the current motor compensation x/y/z values.
|
/// Saves the current motor compensation x/y/z values.
|
||||||
///
|
///
|
||||||
|
@ -228,7 +228,7 @@ public:
|
||||||
/// @returns The current compass offsets.
|
/// @returns The current compass offsets.
|
||||||
///
|
///
|
||||||
const Vector3f &get_motor_offsets(uint8_t i) const { return _motor_offset[i]; }
|
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()); }
|
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
|
/// 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
|
/// @param thr_pct throttle expressed as a percentage from 0 to 1.0
|
||||||
|
@ -253,13 +253,18 @@ public:
|
||||||
bool configured(uint8_t i);
|
bool configured(uint8_t i);
|
||||||
bool configured(void);
|
bool configured(void);
|
||||||
|
|
||||||
|
/// Returns the instance of the primary compass
|
||||||
|
///
|
||||||
|
/// @returns the instance number of the primary compass
|
||||||
|
///
|
||||||
|
virtual uint8_t get_primary(void) const { return 0; }
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
// settable parameters
|
// settable parameters
|
||||||
AP_Int8 _learn; ///<enable calibration learning
|
AP_Int8 _learn; ///<enable calibration learning
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
virtual uint8_t _get_primary(void) const { return 0; }
|
|
||||||
|
|
||||||
bool _healthy[COMPASS_MAX_INSTANCES];
|
bool _healthy[COMPASS_MAX_INSTANCES];
|
||||||
Vector3f _field[COMPASS_MAX_INSTANCES]; ///< magnetic field strength
|
Vector3f _field[COMPASS_MAX_INSTANCES]; ///< magnetic field strength
|
||||||
|
|
Loading…
Reference in New Issue