Browse Source

Compass: use const references for some functions

master
Andrew Tridgell 12 years ago
parent
commit
26fa5c40f1
  1. 4
      libraries/AP_Compass/Compass.cpp
  2. 4
      libraries/AP_Compass/Compass.h

4
libraries/AP_Compass/Compass.cpp

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

4
libraries/AP_Compass/Compass.h

@ -91,7 +91,7 @@ public: @@ -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: @@ -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;
}

Loading…
Cancel
Save