Copter: remove intermediate variable from throw mode

This commit is contained in:
murata 2016-11-03 09:23:26 +09:00 committed by Randy Mackay
parent c5407462d1
commit 1df8acf5cd
1 changed files with 1 additions and 2 deletions

View File

@ -252,8 +252,7 @@ bool Copter::throw_attitude_good()
{ {
// Check that we have uprighted the copter // Check that we have uprighted the copter
const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned(); const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned();
bool is_upright = (rotMat.c.z > 0.866f); return (rotMat.c.z > 0.866f); // is_upright
return is_upright;
} }
bool Copter::throw_height_good() bool Copter::throw_height_good()