From 1df8acf5cde0efe38085d2959573d59d054b0bca Mon Sep 17 00:00:00 2001 From: murata Date: Thu, 3 Nov 2016 09:23:26 +0900 Subject: [PATCH] Copter: remove intermediate variable from throw mode --- ArduCopter/control_throw.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduCopter/control_throw.cpp b/ArduCopter/control_throw.cpp index 8192b0fb66..ed48ffa021 100644 --- a/ArduCopter/control_throw.cpp +++ b/ArduCopter/control_throw.cpp @@ -252,8 +252,7 @@ bool Copter::throw_attitude_good() { // Check that we have uprighted the copter const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned(); - bool is_upright = (rotMat.c.z > 0.866f); - return is_upright; + return (rotMat.c.z > 0.866f); // is_upright } bool Copter::throw_height_good()