AP_Gimbal: Relax minimal angle constrains on the gimbal

This commit is contained in:
Arthur Benemann 2015-03-26 18:05:53 -07:00 committed by Randy Mackay
parent a05fe7e117
commit 9b94f26583

View File

@ -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;
}