mirror of https://github.com/ArduPilot/ardupilot
Compass: save_offsets accepts compass instance
This commit is contained in:
parent
2c1fa5f1e8
commit
124bd4b489
|
@ -166,13 +166,19 @@ Compass::set_offsets(const Vector3f &offsets)
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Compass::save_offsets()
|
Compass::save_offsets(uint8_t i)
|
||||||
{
|
{
|
||||||
for (uint8_t k=0; k<COMPASS_MAX_INSTANCES; k++) {
|
_offset[i].save(); // save offsets
|
||||||
_offset[k].save(); // save offsets
|
|
||||||
#if COMPASS_MAX_INSTANCES > 1
|
#if COMPASS_MAX_INSTANCES > 1
|
||||||
_dev_id[k].save(); // save device id corresponding to these offsets
|
_dev_id[i].save(); // save device id corresponding to these offsets
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Compass::save_offsets(void)
|
||||||
|
{
|
||||||
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
||||||
|
save_offsets(i);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -112,12 +112,15 @@ public:
|
||||||
///
|
///
|
||||||
void set_offsets(const Vector3f &offsets);
|
void set_offsets(const Vector3f &offsets);
|
||||||
|
|
||||||
/// Saves the current compass offset x/y/z values.
|
/// 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
|
/// This should be invoked periodically to save the offset values maintained by
|
||||||
/// ::learn_offsets.
|
/// ::learn_offsets.
|
||||||
///
|
///
|
||||||
void save_offsets();
|
void save_offsets(uint8_t i);
|
||||||
|
void save_offsets(void);
|
||||||
|
|
||||||
// return the number of compass instances
|
// return the number of compass instances
|
||||||
virtual uint8_t get_count(void) const { return 1; }
|
virtual uint8_t get_count(void) const { return 1; }
|
||||||
|
|
Loading…
Reference in New Issue