AC_PosControl: get_accel_target returns const ref

This commit is contained in:
Randy Mackay 2014-04-11 17:14:51 +09:00
parent f5a68fdba1
commit 02775e8dc5

View File

@ -180,14 +180,14 @@ public:
float get_pitch() const { return _pitch_target; }
// get_leash_xy - returns horizontal leash length in cm
float get_leash_xy() { return _leash; }
float get_leash_xy() const { return _leash; }
/// get_pos_xy_kP - returns xy position controller's kP gain
float get_pos_xy_kP() const { return _p_pos_xy.kP(); }
/// accessors for reporting
const Vector3f get_vel_target() { return _vel_target; }
const Vector3f get_accel_target() { return _accel_target; }
const Vector3f& get_vel_target() const { return _vel_target; }
const Vector3f& get_accel_target() const { return _accel_target; }
static const struct AP_Param::GroupInfo var_info[];