AP_InertialSensor: use const reference returns

saves some vector copies
This commit is contained in:
Andrew Tridgell 2013-11-04 14:36:50 +11:00 committed by Randy Mackay
parent a18582673d
commit fc920df8d4

View File

@ -83,7 +83,7 @@ public:
///
/// @returns vector of rotational rates in radians/sec
///
Vector3f get_gyro(void) const { return _gyro; }
const Vector3f &get_gyro(void) const { return _gyro; }
void set_gyro(Vector3f gyro) { _gyro = gyro; }
// set gyro offsets in radians/sec
@ -94,7 +94,7 @@ public:
///
/// @returns vector of current accelerations in m/s/s
///
Vector3f get_accel(void) const { return _accel; }
const Vector3f &get_accel(void) const { return _accel; }
void set_accel(Vector3f accel) { _accel = accel; }
// get accel offsets in m/s/s