Go to the documentation of this file.
47 std::string mode =
init.SweepMode;
48 if (mode ==
"Forwardly")
50 else if (mode ==
"Symmetric")
52 else if (mode ==
"LocalGaussNewton")
54 else if (mode ==
"LocalGaussNewtonDamped")
75 if (problem->type() !=
"exotica::UnconstrainedTimeIndexedProblem")
77 ThrowNamed(
"This solver can't use problem of type '" << problem->type() <<
"'!");
80 prob_ = std::static_pointer_cast<UnconstrainedTimeIndexedProblem>(problem);
92 Eigen::VectorXd q0 =
prob_->ApplyStartState();
93 std::vector<Eigen::VectorXd> q_init =
prob_->GetInitialTrajectory();
98 if (!q0.isApprox(q_init[0]))
101 q_init.assign(
prob_->GetT(), q0);
108 prob_->SetStartState(q_init[0]);
109 prob_->ApplyStartState();
119 if (
prob_->GetT() <= 0)
121 ThrowNamed(
"Problem has not been initialized properly: T=0!");
149 if (
debug_)
HIGHLIGHT(
"Maximum backtrack iterations reached, exiting.");
195 for (
int tt = 0; tt <
prob_->GetT(); ++tt)
205 if (
prob_ ==
nullptr)
ThrowNamed(
"Problem definition is a NULL pointer!");
211 if (
prob_->GetT() < 2)
216 s.assign(
prob_->GetT(), Eigen::VectorXd::Zero(
prob_->N));
218 Sinv[0].diagonal().setConstant(1e10);
219 v.assign(
prob_->GetT(), Eigen::VectorXd::Zero(
prob_->N));
231 WARNING(
"Backward message initialisation skipped, matrices have incorrect dimensions.");
234 b.assign(
prob_->GetT(), Eigen::VectorXd::Zero(
prob_->N));
237 Binv[0].setIdentity();
239 r.assign(
prob_->GetT(), Eigen::VectorXd::Zero(
prob_->N));
241 rhat = Eigen::VectorXd::Zero(
prob_->GetT());
251 for (
int t = 0;
t <
prob_->GetT(); ++
t)
262 if (q_init.size() !=
static_cast<std::size_t
>(
prob_->GetT()))
264 ThrowNamed(
"Incorrect number of timesteps provided!");
272 for (
int t = 1;
t <
prob_->GetT(); ++
t)
274 Sinv.at(
t).setZero();
277 for (
int t = 0;
t <
prob_->GetT(); ++
t)
279 Vinv.at(
t).setZero();
282 for (
int t = 0;
t <
prob_->GetT(); ++
t)
318 if (t < prob_->GetT() - 1)
325 if (
t ==
prob_->GetT() - 1)
330 Vinv[
t].diagonal().setConstant(1);
341 const Eigen::Ref<const Eigen::VectorXd>& qhat_t,
double tolerance,
342 double max_step_size)
344 Eigen::VectorXd diff = qhat_t -
qhat[
t];
345 if ((diff.array().abs().maxCoeff() <
tolerance))
return;
346 double nrm = diff.norm();
347 if (max_step_size > 0. && nrm > max_step_size)
349 qhat[
t] += diff * (max_step_size / nrm);
359 q_stat_[
t].addw(c > 0 ? 1.0 / (1.0 + c) : 1.0, qhat_t);
370 for (
int i = 0; i <
prob_->cost.num_tasks; ++i)
372 prec =
prob_->cost.rho[
t](i);
375 int start =
prob_->cost.indexing[i].start_jacobian;
376 int len =
prob_->cost.indexing[i].length_jacobian;
377 Jt =
prob_->cost.jacobian[
t].middleRows(
start, len).transpose();
378 C += prec * (
prob_->cost.ydiff[
t].segment(
start, len)).squaredNorm();
379 R[
t] += prec * Jt *
prob_->cost.jacobian[
t].middleRows(
start, len);
384 return prob_->get_ct() * C;
388 int max_relocation_iterations,
double tolerance,
bool force_relocation,
389 double max_step_size)
407 if (!((!k && force_relocation) || (
b[
t] -
qhat[
t]).array().abs().maxCoeff() >
tolerance))
break;
429 bool update_bwd,
int max_relocation_iterations,
double tolerance,
430 double max_step_size)
447 for (
int t = 0;
t <
prob_->GetT(); ++
t)
450 if (!
q[
t].allFinite())
452 ThrowNamed(
"q[" <<
t <<
"] is not finite: " <<
q[
t].transpose());
459 for (
int t = 1;
t <
prob_->GetT(); ++
t)
486 for (
t =
prob_->GetT() - 2;
t > 0;
t--)
498 for (
t =
prob_->GetT() - 2;
t > 0;
t--)
508 for (
t =
prob_->GetT() - 2;
t > 0;
t--)
519 for (
t =
prob_->GetT() - 2;
t > 0;
t--)
528 for (
t = 0; t < static_cast<int>(
b.size()); ++
t)
543 if (
cost_ < 0)
return -1.0;
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.
@ BacktrackIterationLimit
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.
#define REGISTER_MOTIONSOLVER_TYPE(TYPE, DERIV)
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)
#define ROS_WARN_STREAM(args)
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)
int GetNumberOfMaxIterations()
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
Approximate Inference Control.
int last_T_
T the last time InitMessages was called.
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
static void inverseSymPosDef(T1 &Ainv, const T2 &A)
Computes an inverse of a symmetric positive definite matrix.
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.
virtual void SpecifyProblem(PlanningProblemPtr pointer)
double step_tolerance_
Relative step tolerance (termination criterion)
geometry_msgs::TransformStamped t
double GetDuration() const
std::vector< Eigen::VectorXd > damping_reference_
Damping reference point.
void UpdateBwdMessage(int t)
Updates the backward message at time step $t$.
static void AinvBSymPosDef(T1 &x, const T2 &A, const T3 &b)
Computes the solution to the linear problem for symmetric positive definite matrix A.