Compass: use const references for some functions

This commit is contained in:
Andrew Tridgell 2013-04-21 22:24:26 +10:00
parent 1849aca0e9
commit 26fa5c40f1
2 changed files with 4 additions and 4 deletions

View File

@ -123,8 +123,8 @@ Compass::save_offsets()
_offset.save();
}
Vector3f &
Compass::get_offsets()
const Vector3f &
Compass::get_offsets() const
{
return _offset;
}

View File

@ -91,7 +91,7 @@ public:
///
/// @returns The current compass offsets.
///
Vector3f &get_offsets();
const Vector3f &get_offsets() const;
/// Sets the initial location used to get declination
///
@ -156,7 +156,7 @@ public:
void set_motor_compensation(const Vector3f &motor_comp_factor);
/// get motor compensation factors as a vector
Vector3f& get_motor_compensation() {
const Vector3f& get_motor_compensation() const {
return _motor_compensation;
}