From 9b94f265839c5e06fad4938ce7d8767577312283 Mon Sep 17 00:00:00 2001 From: Arthur Benemann Date: Thu, 26 Mar 2015 18:05:53 -0700 Subject: [PATCH] AP_Gimbal: Relax minimal angle constrains on the gimbal --- libraries/AP_Gimbal/AP_Gimbal.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_Gimbal/AP_Gimbal.cpp b/libraries/AP_Gimbal/AP_Gimbal.cpp index ada48c9d04..aef165215a 100644 --- a/libraries/AP_Gimbal/AP_Gimbal.cpp +++ b/libraries/AP_Gimbal/AP_Gimbal.cpp @@ -168,11 +168,10 @@ void AP_Gimbal::update_target(Vector3f newTarget) // Low-pass filter _angle_ef_target_rad.y = _angle_ef_target_rad.y + 0.02f*(newTarget.y - _angle_ef_target_rad.y); // Update tilt - _angle_ef_target_rad.y = constrain_float(_angle_ef_target_rad.y,radians(-45),radians(0)); + _angle_ef_target_rad.y = constrain_float(_angle_ef_target_rad.y,radians(-90),radians(0)); } - uint8_t AP_Gimbal::isCopterFliped(){ return fabs(_ahrs.roll)>1.0f || fabs(_ahrs.pitch)>1.0f; } \ No newline at end of file