AC_AttControl: make ahrs, ins objects const

This commit is contained in:
Randy Mackay 2014-01-27 14:08:59 +09:00 committed by Andrew Tridgell
parent 864f64b61a
commit 468be05867
2 changed files with 4 additions and 4 deletions

View File

@ -300,7 +300,7 @@ void AC_AttitudeControl::rate_stab_bf_to_rate_bf_yaw()
//
// rate_ef_targets_to_bf - converts earth frame rate targets to body frame rate targets
void AC_AttitudeControl::rate_ef_targets_to_bf(Vector3f rate_ef_target, Vector3f &rate_bf_target)
void AC_AttitudeControl::rate_ef_targets_to_bf(const Vector3f& rate_ef_target, Vector3f& rate_bf_target)
{
// convert earth frame rates to body frame rates
rate_bf_target.x = rate_ef_target.x - _sin_pitch * rate_ef_target.z;

View File

@ -144,7 +144,7 @@ public:
void rate_ef_targets(Vector3f& rates_cds) { _rate_ef_target = rates_cds; }
// rate_ef_targets_to_bf - converts earth frame rate targets to body frame rate targets
void rate_ef_targets_to_bf(Vector3f rate_ef_target, Vector3f &rate_bf_target);
void rate_ef_targets_to_bf(const Vector3f& rate_ef_target, Vector3f &rate_bf_target);
//
@ -227,8 +227,8 @@ private:
} log_ACAttControl;
// references to external libraries
AP_AHRS& _ahrs;
AP_InertialSensor& _ins;
const AP_AHRS& _ahrs;
const AP_InertialSensor& _ins;
const AP_Vehicle::MultiCopter &_aparm;
AP_Motors& _motors;
APM_PI& _pi_angle_roll;