AP_Compass: added set_offsets() interface
this will be used by Replay to prevent the need for saving parameters
This commit is contained in:
parent
6690aff305
commit
b437977547
@ -289,6 +289,15 @@ Compass::init()
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Compass::set_offsets(uint8_t i, const Vector3f &offsets)
|
||||||
|
{
|
||||||
|
// sanity check compass instance provided
|
||||||
|
if (i < COMPASS_MAX_INSTANCES) {
|
||||||
|
_offset[i].set(offsets);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Compass::set_and_save_offsets(uint8_t i, const Vector3f &offsets)
|
Compass::set_and_save_offsets(uint8_t i, const Vector3f &offsets)
|
||||||
{
|
{
|
||||||
|
@ -87,6 +87,13 @@ public:
|
|||||||
///
|
///
|
||||||
float calculate_heading(const Matrix3f &dcm_matrix) const;
|
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.
|
/// Sets and saves the compass offset x/y/z values.
|
||||||
///
|
///
|
||||||
/// @param i compass instance
|
/// @param i compass instance
|
||||||
|
Loading…
Reference in New Issue
Block a user