#include <levenberg_marquardt_solver.h>

Public Member Functions | |
| void | Solve (Eigen::MatrixXd &solution) override |
| void | SpecifyProblem (PlanningProblemPtr pointer) override |
Public Member Functions inherited from exotica::MotionSolver | |
| int | GetNumberOfMaxIterations () |
| double | GetPlanningTime () |
| PlanningProblemPtr | GetProblem () const |
| void | InstantiateBase (const Initializer &init) override |
| MotionSolver ()=default | |
| std::string | Print (const std::string &prepend) const override |
| void | SetNumberOfMaxIterations (int max_iter) |
| virtual | ~MotionSolver ()=default |
Public Member Functions inherited from exotica::Object | |
| std::string | GetObjectName () |
| void | InstantiateObject (const Initializer &init) |
| Object () | |
| virtual std::string | type () const |
| virtual | ~Object () |
Public Member Functions inherited from exotica::InstantiableBase | |
| InstantiableBase ()=default | |
| virtual | ~InstantiableBase ()=default |
Public Member Functions inherited from exotica::Instantiable< LevenbergMarquardtSolverInitializer > | |
| std::vector< Initializer > | GetAllTemplates () const override |
| Initializer | GetInitializerTemplate () override |
| const LevenbergMarquardtSolverInitializer & | GetParameters () const |
| virtual void | Instantiate (const LevenbergMarquardtSolverInitializer &init) |
| void | InstantiateInternal (const Initializer &init) override |
Private Attributes | |
| Eigen::MatrixXd | cost_jacobian_ |
| Jacobian, used during optimisation. More... | |
| double | error_ |
| Error, used during optimisation. More... | |
| double | error_prev_ |
| Previous iteration error, used during optimisation. More... | |
| Eigen::MatrixXd | JT_times_J_ |
| Gauss-Newton Hessian approximation (J^T * J) More... | |
| double | lambda_ = 0 |
| Damping factor. More... | |
| Eigen::LLT< Eigen::MatrixXd > | llt_ |
| Cholesky decomposition for J^T*J. More... | |
| Eigen::MatrixXd | M_ |
| Scaling matrix, used for regularisation. More... | |
| UnconstrainedEndPoseProblemPtr | prob_ |
| Shared pointer to the planning problem. More... | |
| Eigen::VectorXd | q_ |
| Joint configuration vector, used during optimisation. More... | |
| Eigen::VectorXd | qd_ |
| Change in joint configuration, used during optimisation. More... | |
| Eigen::VectorXd | yd_ |
| Task space difference/error, used during optimisation. More... | |
Additional Inherited Members | |
Public Attributes inherited from exotica::Object | |
| bool | debug_ |
| std::string | ns_ |
| std::string | object_name_ |
Protected Attributes inherited from exotica::MotionSolver | |
| int | max_iterations_ |
| double | planning_time_ |
| PlanningProblemPtr | problem_ |
Protected Attributes inherited from exotica::Instantiable< LevenbergMarquardtSolverInitializer > | |
| LevenbergMarquardtSolverInitializer | parameters_ |
Definition at line 33 of file levenberg_marquardt_solver.h.
|
overridevirtual |
Implements exotica::MotionSolver.
Definition at line 71 of file levenberg_marquardt_solver.cpp.
|
overridevirtual |
Reimplemented from exotica::MotionSolver.
Definition at line 29 of file levenberg_marquardt_solver.cpp.
|
private |
Jacobian, used during optimisation.
Definition at line 50 of file levenberg_marquardt_solver.h.
|
private |
Error, used during optimisation.
Definition at line 51 of file levenberg_marquardt_solver.h.
|
private |
Previous iteration error, used during optimisation.
Definition at line 52 of file levenberg_marquardt_solver.h.
|
private |
Gauss-Newton Hessian approximation (J^T * J)
Definition at line 46 of file levenberg_marquardt_solver.h.
|
private |
Damping factor.
Definition at line 44 of file levenberg_marquardt_solver.h.
|
private |
Cholesky decomposition for J^T*J.
Definition at line 53 of file levenberg_marquardt_solver.h.
|
private |
Scaling matrix, used for regularisation.
Definition at line 45 of file levenberg_marquardt_solver.h.
|
private |
Shared pointer to the planning problem.
Definition at line 41 of file levenberg_marquardt_solver.h.
|
private |
Joint configuration vector, used during optimisation.
Definition at line 47 of file levenberg_marquardt_solver.h.
|
private |
Change in joint configuration, used during optimisation.
Definition at line 48 of file levenberg_marquardt_solver.h.
|
private |
Task space difference/error, used during optimisation.
Definition at line 49 of file levenberg_marquardt_solver.h.