Go to the documentation of this file.
55 #ifndef EXOTICA_AICO_SOLVER_AICO_SOLVER_H_
56 #define EXOTICA_AICO_SOLVER_AICO_SOLVER_H_
66 #include <exotica_aico_solver/aico_solver_initializer.h>
81 void Solve(Eigen::MatrixXd& solution)
override;
113 std::vector<SinglePassMeanCovariance>
q_stat_;
115 std::vector<Eigen::VectorXd>
s;
116 std::vector<Eigen::MatrixXd>
Sinv;
117 std::vector<Eigen::VectorXd>
v;
118 std::vector<Eigen::MatrixXd>
Vinv;
119 std::vector<Eigen::VectorXd>
r;
120 std::vector<Eigen::MatrixXd>
R;
122 std::vector<Eigen::VectorXd>
b;
123 std::vector<Eigen::MatrixXd>
Binv;
124 std::vector<Eigen::VectorXd>
q;
125 std::vector<Eigen::VectorXd>
qhat;
199 const Eigen::Ref<const Eigen::VectorXd>& qhat_t,
double tolerance,
200 double max_step_size = -1.);
211 int max_relocation_iterations,
double tolerance,
bool force_relocation,
212 double max_step_size = -1.);
229 int max_relocation_iterations,
double tolerance,
double max_step_size = -1.);
234 double EvaluateTrajectory(
const std::vector<Eigen::VectorXd>& x,
bool skip_update =
false);
252 #endif // EXOTICA_AICO_SOLVER_AICO_SOLVER_H_
Eigen::VectorXd cost_task_
Task cost for each task for each time step.
Eigen::VectorXd cost_control_old_
Control cost for each time step (last most optimal value)
std::vector< Eigen::VectorXd > q
Configuration space trajectory.
void InitTrajectory(const std::vector< Eigen::VectorXd > &q_init)
Initialise AICO messages from an initial trajectory.
Eigen::MatrixXd bwd_msg_Vinv_
Backward message initialisation covariance.
void UpdateTimestepGaussNewton(int t, 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.
double EvaluateTrajectory(const std::vector< Eigen::VectorXd > &x, bool skip_update=false)
Computes the cost of the trajectory.
double damping_init_
Damping.
Solves motion planning problem using Approximate Inference Control method.
void UpdateTaskMessage(int t, const Eigen::Ref< const Eigen::VectorXd > &qhat_t, double tolerance, double max_step_size=-1.)
void PerhapsUndoStep()
Reverts back to previous state if the cost of the current state is higher.
Eigen::MatrixXd cost_task_old_
Task cost for each task for each time step (last most optimal value)
std::vector< Eigen::MatrixXd > Vinv_old
Backward message covariance inverse (last most optimal value)
int max_backtrack_iterations_
Max. number of sweeps without improvement before terminating (= line-search)
Eigen::VectorXd cost_control_
Control cost for each time step.
std::vector< Eigen::MatrixXd > R
Task message covariance.
double Step()
Compute one step of the AICO algorithm.
bool sweep_improved_cost_
Whether the last sweep improved the cost (for backtrack iterations count)
std::vector< Eigen::MatrixXd > Binv
Belief covariance inverse.
double minimum_step_tolerance_
Update tolerance to stop update of messages if change of maximum coefficient is less than this tolera...
Eigen::MatrixXd W
Configuration space weight matrix inverse.
void InitMessages()
Initializes message data.
std::vector< Eigen::VectorXd > qhat_old
Point of linearisation (last most optimal value)
std::vector< Eigen::VectorXd > qhat
Point of linearisation.
double b_step_
Squared configuration space step.
void UpdateFwdMessage(int t)
Updates the forward message at time step $t$.
std::vector< Eigen::MatrixXd > Sinv_old
Forward message covariance inverse (last most optimal value)
std::vector< Eigen::MatrixXd > Binv_old
Belief covariance inverse (last most optimal value)
double cost_old_
cost of MAP trajectory (last most optimal value)
void Instantiate(const AICOSolverInitializer &init) override
std::vector< Eigen::VectorXd > q_old
Configuration space trajectory (last most optimal value)
Eigen::VectorXd rhat_old
Task message point of linearisation (last most optimal value)
void SpecifyProblem(PlanningProblemPtr pointer) override
Binds the solver to a specific problem which must be pre-initalised.
std::vector< Eigen::MatrixXd > Vinv
Backward message covariance inverse.
std::vector< Eigen::VectorXd > v_old
Backward message mean (last most optimal value)
Eigen::VectorXd bwd_msg_v_
Backward message initialisation mean.
double cost_
cost of MAP trajectory
int last_T_
T the last time InitMessages was called.
std::shared_ptr< exotica::UnconstrainedTimeIndexedProblem > UnconstrainedTimeIndexedProblemPtr
std::vector< Eigen::VectorXd > b
Belief mean.
std::vector< Eigen::VectorXd > s
Forward message mean.
int iteration_count_
Iteration counter.
double cost_prev_
previous iteration cost
void Solve(Eigen::MatrixXd &solution) override
Solves the problem.
std::vector< Eigen::MatrixXd > R_old
Task message covariance (last most optimal value)
UnconstrainedTimeIndexedProblemPtr prob_
Shared pointer to the planning problem.
int sweep_mode_
Sweep mode.
std::shared_ptr< PlanningProblem > PlanningProblemPtr
std::vector< Eigen::VectorXd > v
Backward message mean.
Eigen::MatrixXd Winv
Configuration space weight matrix inverse.
void UpdateTimestep(int t, 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.
@ LOCAL_GAUSS_NEWTON_DAMPED
double GetTaskCosts(int t)
Updates the task cost terms for time step . UnconstrainedTimeIndexedProblem::Update() has to be call...
std::vector< Eigen::VectorXd > b_old
Belief mean (last most optimal value)
std::vector< Eigen::VectorXd > r
Task message mean.
Eigen::VectorXd rhat
Task message point of linearisation.
std::vector< SinglePassMeanCovariance > q_stat_
Cost weighted normal distribution of configurations across sweeps.
double function_tolerance_
Relative function tolerance/first-order optimality criterion.
void init(const M_string &remappings)
void RememberOldState()
Stores the previous state.
std::vector< Eigen::VectorXd > s_old
Forward message mean (last most optimal value)
bool use_bwd_msg_
Flag for using backward message initialisation.
std::vector< Eigen::VectorXd > r_old
Task message mean (last most optimal value)
std::vector< Eigen::MatrixXd > Sinv
Forward message covariance inverse.
double step_tolerance_
Relative step tolerance (termination criterion)
std::vector< Eigen::VectorXd > damping_reference_
Damping reference point.
void UpdateBwdMessage(int t)
Updates the backward message at time step $t$.