#pragma once #include namespace drake { namespace math { /// Computes the unique stabilizing solution S to the continuous-time algebraic /// Riccati equation: /// /// @f[ /// S A + A' S - S B R^{-1} B' S + Q = 0 /// @f] /// /// @throws std::exception if R is not positive definite. /// /// Based on the Matrix Sign Function method outlined in this paper: /// http://www.engr.iupui.edu/~skoskie/ECE684/Riccati_algorithms.pdf /// Eigen::MatrixXd ContinuousAlgebraicRiccatiEquation( const Eigen::Ref& A, const Eigen::Ref& B, const Eigen::Ref& Q, const Eigen::Ref& R); /// This is functionally the same as /// ContinuousAlgebraicRiccatiEquation(A, B, Q, R). /// The Cholesky decomposition of R is passed in instead of R. Eigen::MatrixXd ContinuousAlgebraicRiccatiEquation( const Eigen::Ref& A, const Eigen::Ref& B, const Eigen::Ref& Q, const Eigen::LLT& R_cholesky); } // namespace math } // namespace drake