|
Exotica
|
Solves motion planning problem using Approximate Inference Control method. More...
#include <bayesian_ik_solver.h>


Public Member Functions | |
| void | Instantiate (const BayesianIKSolverInitializer &init) override |
| void | Solve (Eigen::MatrixXd &solution) override |
| Solves the problem. More... | |
| void | SpecifyProblem (PlanningProblemPtr pointer) override |
| Binds the solver to a specific problem which must be pre-initalised. More... | |
Public Member Functions inherited from exotica::MotionSolver | |
| MotionSolver ()=default | |
| virtual | ~MotionSolver ()=default |
| void | InstantiateBase (const Initializer &init) override |
| PlanningProblemPtr | GetProblem () const |
| std::string | Print (const std::string &prepend) const override |
| void | SetNumberOfMaxIterations (int max_iter) |
| int | GetNumberOfMaxIterations () |
| double | GetPlanningTime () |
Public Member Functions inherited from exotica::Object | |
| Object () | |
| virtual | ~Object () |
| virtual std::string | type () const |
| Type Information wrapper: must be virtual so that it is polymorphic... More... | |
| std::string | GetObjectName () |
| void | InstantiateObject (const Initializer &init) |
Public Member Functions inherited from exotica::InstantiableBase | |
| InstantiableBase ()=default | |
| virtual | ~InstantiableBase ()=default |
| virtual std::vector< Initializer > | GetAllTemplates () const =0 |
Public Member Functions inherited from exotica::Instantiable< BayesianIKSolverInitializer > | |
| void | InstantiateInternal (const Initializer &init) override |
| Initializer | GetInitializerTemplate () override |
| std::vector< Initializer > | GetAllTemplates () const override |
| const BayesianIKSolverInitializer & | GetParameters () const |
Protected Member Functions | |
| void | InitMessages () |
| Initializes message data. More... | |
| void | InitTrajectory (const Eigen::VectorXd &q_init) |
| Initialise AICO messages from an initial trajectory. More... | |
Private Types | |
| enum | SweepMode { FORWARD = 0, SYMMETRIC, LOCAL_GAUSS_NEWTON, LOCAL_GAUSS_NEWTON_DAMPED } |
Private Member Functions | |
| void | UpdateFwdMessage () |
Updates the forward message Updates the mean and covariance of the forward message using: , where and . More... | |
| void | UpdateBwdMessage () |
Updates the backward message Updates the mean and covariance of the backward message using: , where and . More... | |
| void | UpdateTaskMessage (const Eigen::Ref< const Eigen::VectorXd > &qhat_t, double tolerance, double max_step_size=-1.) |
| Updates the task message. More... | |
| void | UpdateTimestep (bool update_fwd, bool update_bwd, int max_relocation_iterations, double tolerance, bool force_relocation, double max_step_size=-1.) |
| Update messages for given time step. More... | |
| void | UpdateTimestepGaussNewton (bool update_fwd, bool update_bwd, int max_relocation_iterations, double tolerance, double max_step_size=-1.) |
| Update messages for given time step using the Gauss Newton method. More... | |
| double | EvaluateTrajectory (const Eigen::VectorXd &x, bool skip_update=false) |
| Computes the cost of the trajectory. More... | |
| void | RememberOldState () |
| Stores the previous state. More... | |
| void | PerhapsUndoStep () |
| Reverts back to previous state if the cost of the current state is higher. More... | |
| void | GetTaskCosts () |
Updates the task cost terms . UnconstrainedEndPoseProblem::Update() has to be called before calling this function. More... | |
| double | Step () |
| Compute one step of the AICO algorithm. More... | |
Private Attributes | |
| UnconstrainedEndPoseProblemPtr | prob_ |
| Shared pointer to the planning problem. More... | |
| double | damping = 0.01 |
| Damping. More... | |
| double | damping_init_ = 100.0 |
| Damping. More... | |
| double | minimum_step_tolerance_ = 1e-5 |
| Update tolerance to stop update of messages if change of maximum coefficient is less than this tolerance. More... | |
| double | step_tolerance_ = 1e-5 |
| Relative step tolerance (termination criterion) More... | |
| double | function_tolerance_ = 1e-5 |
| Relative function tolerance/first-order optimality criterion. More... | |
| int | max_backtrack_iterations_ = 10 |
| Max. number of sweeps without improvement before terminating (= line-search) More... | |
| bool | use_bwd_msg_ = false |
| Flag for using backward message initialisation. More... | |
| Eigen::VectorXd | bwd_msg_v_ |
| Backward message initialisation mean. More... | |
| Eigen::MatrixXd | bwd_msg_Vinv_ |
| Backward message initialisation covariance. More... | |
| bool | sweep_improved_cost_ |
| Whether the last sweep improved the cost (for backtrack iterations count) More... | |
| int | iteration_count_ |
| Iteration counter. More... | |
| Eigen::VectorXd | s |
| Forward message mean. More... | |
| Eigen::MatrixXd | Sinv |
| Forward message covariance inverse. More... | |
| Eigen::VectorXd | v |
| Backward message mean. More... | |
| Eigen::MatrixXd | Vinv |
| Backward message covariance inverse. More... | |
| Eigen::VectorXd | r |
| Task message mean. More... | |
| Eigen::MatrixXd | R |
| Task message covariance. More... | |
| double | rhat |
| Task message point of linearisation. More... | |
| Eigen::VectorXd | b |
| Belief mean. More... | |
| Eigen::MatrixXd | Binv |
| Belief covariance inverse. More... | |
| Eigen::VectorXd | q |
| Configuration space trajectory. More... | |
| Eigen::VectorXd | qhat |
| Point of linearisation. More... | |
| Eigen::VectorXd | s_old |
| Forward message mean (last most optimal value) More... | |
| Eigen::MatrixXd | Sinv_old |
| Forward message covariance inverse (last most optimal value) More... | |
| Eigen::VectorXd | v_old |
| Backward message mean (last most optimal value) More... | |
| Eigen::MatrixXd | Vinv_old |
| Backward message covariance inverse (last most optimal value) More... | |
| Eigen::VectorXd | r_old |
| Task message mean (last most optimal value) More... | |
| Eigen::MatrixXd | R_old |
| Task message covariance (last most optimal value) More... | |
| double | rhat_old |
| Task message point of linearisation (last most optimal value) More... | |
| Eigen::VectorXd | b_old |
| Belief mean (last most optimal value) More... | |
| Eigen::MatrixXd | Binv_old |
| Belief covariance inverse (last most optimal value) More... | |
| Eigen::VectorXd | q_old |
| Configuration space trajectory (last most optimal value) More... | |
| Eigen::VectorXd | qhat_old |
| Point of linearisation (last most optimal value) More... | |
| Eigen::VectorXd | damping_reference_ |
| Damping reference point. More... | |
| double | cost_ = 0.0 |
| cost of MAP trajectory More... | |
| double | cost_old_ = std::numeric_limits<double>::max() |
| cost of MAP trajectory (last most optimal value) More... | |
| double | cost_prev_ = std::numeric_limits<double>::max() |
| previous iteration cost More... | |
| double | b_step_ = 0.0 |
| Squared configuration space step. More... | |
| double | b_step_old_ |
| Eigen::MatrixXd | W |
| Configuration space weight matrix inverse. More... | |
| Eigen::MatrixXd | Winv |
| Configuration space weight matrix inverse. More... | |
| int | sweep_ = 0 |
| Sweeps so far. More... | |
| int | best_sweep_ = 0 |
| int | best_sweep_old_ = 0 |
| int | sweep_mode_ = 0 |
| Sweep mode. More... | |
| int | update_count_ = 0 |
| bool | verbose_ = false |
Additional Inherited Members | |
Public Attributes inherited from exotica::Object | |
| std::string | ns_ |
| std::string | object_name_ |
| bool | debug_ |
Protected Attributes inherited from exotica::MotionSolver | |
| PlanningProblemPtr | problem_ |
| double | planning_time_ = -1 |
| int | max_iterations_ = 100 |
Protected Attributes inherited from exotica::Instantiable< BayesianIKSolverInitializer > | |
| BayesianIKSolverInitializer | parameters_ |
Solves motion planning problem using Approximate Inference Control method.
|
private |
|
private |
Computes the cost of the trajectory.
| x | Trajecotry. |
|
private |
Updates the task cost terms
. UnconstrainedEndPoseProblem::Update() has to be called before calling this function.
|
protected |
Initializes message data.
| q0 | Start configuration |
|
protected |
Initialise AICO messages from an initial trajectory.
| q_init | Initial trajectory |
|
overridevirtual |
Reimplemented from exotica::Instantiable< BayesianIKSolverInitializer >.
|
private |
Reverts back to previous state if the cost of the current state is higher.
|
private |
Stores the previous state.
|
overridevirtual |
Solves the problem.
| solution | Returned end pose solution. |
Implements exotica::MotionSolver.
|
overridevirtual |
Binds the solver to a specific problem which must be pre-initalised.
| pointer | Shared pointer to the motion planning problem |
Reimplemented from exotica::MotionSolver.
|
private |
Compute one step of the AICO algorithm.
|
private |
Updates the backward message Updates the mean and covariance of the backward message using:
, where
and
.
|
private |
Updates the forward message Updates the mean and covariance of the forward message using:
, where
and
.
|
private |
Updates the task message.
| qhat_t | Point of linearisation at time step $t$ |
| tolerance | Lazy update tolerance (only update the task message if the state changed more than this value) |
| max_step_size | If step size >0, cap the motion at this step to the step size. Updates the mean and covariance of the task message using: |
|
private |
Update messages for given time step.
| t | Time step. |
| update_fwd | Update the forward message. |
| update_bwd | Update the backward message. |
| max_relocation_iterations | Maximum number of relocation while searching for a good linearisation point |
| tolerance | Tolerance for for stopping the search. |
| force_relocation | Set to true to force relocation even when the result is within tolerance. |
| max_step_size | Step size for UpdateTaskMessage. |
|
private |
Update messages for given time step using the Gauss Newton method.
| t | Time step. |
| update_fwd | Update the forward message. |
| update_bwd | Update the backward message. |
| max_relocation_iterations | Maximum number of relocation while searching for a good linearisation point |
| tolerance | Tolerance for for stopping the search. |
| max_step_size | Step size for UpdateTaskMessage. First, the messages , and are computed. Then, the belief is updated: where the mean and covariance are updated as follows: . |
|
private |
Belief mean.
|
private |
Belief mean (last most optimal value)
|
private |
Squared configuration space step.
|
private |
|
private |
|
private |
|
private |
Belief covariance inverse.
|
private |
Belief covariance inverse (last most optimal value)
|
private |
Backward message initialisation mean.
|
private |
Backward message initialisation covariance.
|
private |
cost of MAP trajectory
|
private |
cost of MAP trajectory (last most optimal value)
|
private |
previous iteration cost
|
private |
Damping.
|
private |
Damping.
|
private |
Damping reference point.
|
private |
Relative function tolerance/first-order optimality criterion.
|
private |
Iteration counter.
|
private |
Max. number of sweeps without improvement before terminating (= line-search)
|
private |
Update tolerance to stop update of messages if change of maximum coefficient is less than this tolerance.
|
private |
Shared pointer to the planning problem.
|
private |
Configuration space trajectory.
|
private |
Configuration space trajectory (last most optimal value)
|
private |
Point of linearisation.
|
private |
Point of linearisation (last most optimal value)
|
private |
Task message mean.
|
private |
Task message covariance.
|
private |
Task message mean (last most optimal value)
|
private |
Task message covariance (last most optimal value)
|
private |
Task message point of linearisation.
|
private |
Task message point of linearisation (last most optimal value)
|
private |
Forward message mean.
|
private |
Forward message mean (last most optimal value)
|
private |
Forward message covariance inverse.
|
private |
Forward message covariance inverse (last most optimal value)
|
private |
Relative step tolerance (termination criterion)
|
private |
Sweeps so far.
|
private |
Whether the last sweep improved the cost (for backtrack iterations count)
|
private |
Sweep mode.
|
private |
|
private |
Flag for using backward message initialisation.
|
private |
Backward message mean.
|
private |
Backward message mean (last most optimal value)
|
private |
|
private |
Backward message covariance inverse.
|
private |
Backward message covariance inverse (last most optimal value)
|
private |
Configuration space weight matrix inverse.
|
private |
Configuration space weight matrix inverse.
1.8.17