Autoware.Auto
autoware::motion::control::trajectory_follower::QPSolverEigenLeastSquareLLT Class Reference

#include <qp_solver_unconstr_fast.hpp>

Inheritance diagram for autoware::motion::control::trajectory_follower::QPSolverEigenLeastSquareLLT:
Collaboration diagram for autoware::motion::control::trajectory_follower::QPSolverEigenLeastSquareLLT:

Public Member Functions

 QPSolverEigenLeastSquareLLT ()
 constructor More...
 
 ~QPSolverEigenLeastSquareLLT ()=default
 destructor More...
 
bool8_t solve (const Eigen::MatrixXd &h_mat, const Eigen::MatrixXd &f_vec, const Eigen::MatrixXd &a, const Eigen::VectorXd &lb, const Eigen::VectorXd &ub, const Eigen::VectorXd &lb_a, const Eigen::VectorXd &ub_a, Eigen::VectorXd &u) override
 solve QP problem : minimize j = u' * h_mat * u + f_vec' * u without constraint More...
 
- Public Member Functions inherited from autoware::motion::control::trajectory_follower::QPSolverInterface
virtual ~QPSolverInterface ()=default
 destructor More...
 

Detailed Description

Solver for QP problems using least square decomposition implement with Eigen's standard Cholesky decomposition (LLT)

Constructor & Destructor Documentation

◆ QPSolverEigenLeastSquareLLT()

autoware::motion::control::trajectory_follower::QPSolverEigenLeastSquareLLT::QPSolverEigenLeastSquareLLT ( )

constructor

◆ ~QPSolverEigenLeastSquareLLT()

autoware::motion::control::trajectory_follower::QPSolverEigenLeastSquareLLT::~QPSolverEigenLeastSquareLLT ( )
default

destructor

Member Function Documentation

◆ solve()

bool8_t autoware::motion::control::trajectory_follower::QPSolverEigenLeastSquareLLT::solve ( const Eigen::MatrixXd &  h_mat,
const Eigen::MatrixXd &  f_vec,
const Eigen::MatrixXd &  a,
const Eigen::VectorXd &  lb,
const Eigen::VectorXd &  ub,
const Eigen::VectorXd &  lb_a,
const Eigen::VectorXd &  ub_a,
Eigen::VectorXd &  u 
)
overridevirtual

solve QP problem : minimize j = u' * h_mat * u + f_vec' * u without constraint

Parameters
[in]h_matparameter matrix in object function
[in]f_vecparameter matrix in object function
[in]aparameter matrix for constraint lb_a < a*u < ub_a (not used here)
[in]lbparameter matrix for constraint lb < U < ub (not used here)
[in]ubparameter matrix for constraint lb < U < ub (not used here)
[in]lb_aparameter matrix for constraint lb_a < a*u < ub_a (not used here)
[in]ub_aparameter matrix for constraint lb_a < a*u < ub_a (not used here)
[out]uoptimal variable vector
Returns
true if the problem was solved

Implements autoware::motion::control::trajectory_follower::QPSolverInterface.


The documentation for this class was generated from the following files: