abstract_time_indexed_problem.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020, University of Edinburgh, University of Oxford
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
31 #include <exotica_core/setup.h>
32 
33 namespace exotica
34 {
36 {
37  flags_ = KIN_FK | KIN_J;
38 }
39 
41 
43 {
44  return scene_->GetKinematicTree().GetJointLimits();
45 }
46 
48 {
49  if (debug_) HIGHLIGHT_NAMED("TimeIndexedProblem", "Initialize problem with T=" << T_);
50 
51  num_tasks = tasks_.size();
52  length_Phi = 0;
53  length_jacobian = 0;
54  TaskSpaceVector y_ref_;
55  for (int i = 0; i < num_tasks; ++i)
56  {
57  AppendVector(y_ref_.map, tasks_[i]->GetLieGroupIndices());
58  length_Phi += tasks_[i]->length;
59  length_jacobian += tasks_[i]->length_jacobian;
60  }
61 
62  y_ref_.SetZero(length_Phi);
63  Phi.assign(T_, y_ref_);
64 
65  x.assign(T_, Eigen::VectorXd::Zero(N));
66  xdiff.assign(T_, Eigen::VectorXd::Zero(N));
67  if (flags_ & KIN_J) jacobian.assign(T_, Eigen::MatrixXd(length_jacobian, N));
68  if (flags_ & KIN_H)
69  {
70  Hessian Htmp;
71  Htmp.setConstant(length_jacobian, Eigen::MatrixXd::Zero(N, N));
72  hessian.assign(T_, Htmp);
73  }
74 
75  // Set initial trajectory
76  initial_trajectory_.resize(T_, scene_->GetControlledState());
77 
78  // Initialize cost and constraints
79  cost.ReinitializeVariables(T_, shared_from_this(), cost_Phi);
80  inequality.ReinitializeVariables(T_, shared_from_this(), inequality_Phi);
81  equality.ReinitializeVariables(T_, shared_from_this(), equality_Phi);
82 
83  // Initialize joint velocity constraint
86  // The Jacobian is constant so we can allocate the triplets here for the problem:
87  typedef Eigen::Triplet<double> T;
89  for (int t = 1; t < T_; ++t)
90  {
91  for (int n = 0; n < N; ++n)
92  {
93  // x_t+1 ==> 1
94  joint_velocity_constraint_jacobian_triplets_.emplace_back(T((t - 1) * N + n, (t - 1) * N + n, 1.0));
95 
96  if (t > 1)
97  {
98  // x_t => -1
99  joint_velocity_constraint_jacobian_triplets_.emplace_back(T((t - 1) * N + n, (t - 2) * N + n, -1.0));
100  }
101  }
102  }
103 
104  // Updates related to tau
105  ct = 1.0 / tau_ / T_;
107 
108  // Pre-update
109  PreUpdate();
110 }
111 
113 {
114  return T_;
115 }
116 
118 {
119  if (T_in <= 2)
120  {
121  ThrowNamed("Invalid number of timesteps: " << T_in);
122  }
123  T_ = T_in;
125 }
126 
128 {
129  return tau_;
130 }
131 
132 void AbstractTimeIndexedProblem::SetTau(const double tau_in)
133 {
134  if (tau_in <= 0.) ThrowPretty("tau_ is expected to be greater than 0. (tau_=" << tau_in << ")");
135  tau_ = tau_in;
137 }
138 
140 {
142  for (int i = 0; i < tasks_.size(); ++i) tasks_[i]->is_used = false;
143  cost.UpdateS();
145  equality.UpdateS();
146 
147  // Update list of active equality/inequality constraints:
152  for (int t = 1; t < T_; ++t)
153  {
154  for (const TaskIndexing& task : equality.indexing)
155  {
156  if (equality.rho[t](task.id) != 0.0)
157  {
158  active_nonlinear_equality_constraints_.emplace_back(std::make_pair(t, task.id));
160  }
161  }
162 
163  for (const TaskIndexing& task : inequality.indexing)
164  {
165  if (inequality.rho[t](task.id) != 0.0)
166  {
167  active_nonlinear_inequality_constraints_.emplace_back(std::make_pair(t, task.id));
169  }
170  }
171  }
172 
173  // Create a new set of kinematic solutions with the size of the trajectory
174  // based on the lastest KinematicResponse in order to reflect model state
175  // updates etc.
176  kinematic_solutions_.clear();
177  kinematic_solutions_.resize(T_);
178  for (int i = 0; i < T_; ++i) kinematic_solutions_[i] = std::make_shared<KinematicResponse>(*scene_->GetKinematicTree().GetKinematicResponse());
179 }
180 
181 void AbstractTimeIndexedProblem::SetInitialTrajectory(const std::vector<Eigen::VectorXd>& q_init_in)
182 {
183  if (q_init_in.size() != T_)
184  ThrowPretty("Expected initial trajectory of length "
185  << T_ << " but got " << q_init_in.size());
186  if (q_init_in[0].rows() != N)
187  ThrowPretty("Expected states to have " << N << " rows but got "
188  << q_init_in[0].rows());
189 
190  initial_trajectory_ = q_init_in;
191  SetStartState(q_init_in[0]);
192 }
193 
194 std::vector<Eigen::VectorXd> AbstractTimeIndexedProblem::GetInitialTrajectory() const
195 {
196  return initial_trajectory_;
197 }
198 
200 {
201  return tau_ * static_cast<double>(T_);
202 }
203 
205 {
206  if (x_trajectory_in.size() != (T_ - 1) * N)
207  ThrowPretty("To update using the trajectory Update method, please use a trajectory of size N x (T-1) (" << N * (T_ - 1) << "), given: " << x_trajectory_in.size());
208 
209  for (int t = 1; t < T_; ++t)
210  {
211  Update(x_trajectory_in.segment((t - 1) * N, N), t);
212  }
213 }
214 
216 {
218 
219  x[t] = x_in;
220 
221  // Set the corresponding KinematicResponse for KinematicTree in order to
222  // have Kinematics elements updated based in x_in.
223  scene_->GetKinematicTree().SetKinematicResponse(kinematic_solutions_[t]);
224 
225  // Pass the corresponding number of relevant task kinematics to the TaskMaps
226  // via the PlanningProblem::UpdateMultipleTaskKinematics method. For now we
227  // support passing _two_ timesteps - this can be easily changed later on.
228  std::vector<std::shared_ptr<KinematicResponse>> kinematics_solutions{kinematic_solutions_[t]};
229 
230  // If the current timestep is 0, pass the 0th timestep's response twice.
231  // Otherwise pass the (t-1)th response.
232  kinematics_solutions.emplace_back((t == 0) ? kinematic_solutions_[t] : kinematic_solutions_[t - 1]);
233 
234  // Actually update the tasks' kinematics mappings.
235  PlanningProblem::UpdateMultipleTaskKinematics(kinematics_solutions);
236 
237  scene_->Update(x_in, static_cast<double>(t) * tau_);
238  Phi[t].SetZero(length_Phi);
239  if (flags_ & KIN_J) jacobian[t].setZero();
240  if (flags_ & KIN_H)
241  for (int i = 0; i < length_jacobian; ++i) hessian[t](i).setZero();
242  for (int i = 0; i < num_tasks; ++i)
243  {
244  // Only update TaskMap if rho is not 0
245  if (tasks_[i]->is_used)
246  {
247  if (flags_ & KIN_H)
248  {
249  tasks_[i]->Update(x[t],
250  Phi[t].data.segment(tasks_[i]->start, tasks_[i]->length),
251  jacobian[t].middleRows(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian),
252  hessian[t].segment(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian));
253  }
254  else if (flags_ & KIN_J)
255  {
256  tasks_[i]->Update(x[t],
257  Phi[t].data.segment(tasks_[i]->start, tasks_[i]->length),
258  Eigen::MatrixXdRef(jacobian[t].middleRows(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian)) // Adding MatrixXdRef(...) is a work-around for issue #737 when using Eigen 3.3.9
259  );
260  }
261  else
262  {
263  tasks_[i]->Update(x[t], Phi[t].data.segment(tasks_[i]->start, tasks_[i]->length));
264  }
265  }
266  }
267  if (flags_ & KIN_H)
268  {
269  cost.Update(Phi[t], jacobian[t], hessian[t], t);
272  }
273  else if (flags_ & KIN_J)
274  {
275  cost.Update(Phi[t], jacobian[t], t);
277  equality.Update(Phi[t], jacobian[t], t);
278  }
279  else
280  {
281  cost.Update(Phi[t], t);
282  inequality.Update(Phi[t], t);
283  equality.Update(Phi[t], t);
284  }
285  if (t > 0) xdiff[t] = x[t] - x[t - 1];
287 }
288 
290 {
291  return ct;
292 }
293 
295 {
296  double cost = 0.0;
297  for (int t = 1; t < T_; ++t)
298  {
300  }
301  return cost;
302 }
303 
305 {
306  Eigen::RowVectorXd jac = Eigen::RowVectorXd::Zero(N * (T_ - 1));
307  for (int t = 1; t < T_; ++t)
308  {
309  jac.segment((t - 1) * N, N) += GetScalarTaskJacobian(t) + GetScalarTransitionJacobian(t);
310  if (t > 1) jac.segment((t - 2) * N, N) -= GetScalarTransitionJacobian(t);
311  }
312  return jac;
313 }
314 
316 {
318  return ct * cost.ydiff[t].transpose() * cost.S[t] * cost.ydiff[t];
319 }
320 
322 {
324  return cost.jacobian[t].transpose() * cost.S[t] * cost.ydiff[t] * 2.0 * ct;
325 }
326 
328 {
330  return ct * xdiff[t].transpose() * W * xdiff[t];
331 }
332 
334 {
336  return 2.0 * ct * W * xdiff[t];
337 }
338 
340 {
342 }
343 
345 {
347 }
348 
350 {
351  Eigen::VectorXd eq = Eigen::VectorXd::Zero(active_nonlinear_equality_constraints_dimension_);
352  int start = 0;
353  for (const auto& constraint : active_nonlinear_equality_constraints_)
354  {
355  // First is timestep, second is task id
356  const TaskIndexing task = equality.indexing[constraint.second];
357  eq.segment(start, task.length_jacobian) = equality.rho[constraint.first](task.id) * equality.ydiff[constraint.first].segment(task.start_jacobian, task.length_jacobian);
358  start += task.length_jacobian;
359  }
360 
361  return eq;
362 }
363 
364 Eigen::SparseMatrix<double> AbstractTimeIndexedProblem::GetEqualityJacobian() const
365 {
366  Eigen::SparseMatrix<double> jac(active_nonlinear_equality_constraints_dimension_, N * (T_ - 1));
367  std::vector<Eigen::Triplet<double>> triplet_list = GetEqualityJacobianTriplets();
368  jac.setFromTriplets(triplet_list.begin(), triplet_list.end());
369  return jac;
370 }
371 
372 std::vector<Eigen::Triplet<double>> AbstractTimeIndexedProblem::GetEqualityJacobianTriplets() const
373 {
374  typedef Eigen::Triplet<double> T;
375  std::vector<T> triplet_list;
376  triplet_list.reserve(active_nonlinear_equality_constraints_dimension_ * N);
377  int start = 0;
378  for (const auto& constraint : active_nonlinear_equality_constraints_)
379  {
380  // First is timestep, second is task id
381  const TaskIndexing task = equality.indexing[constraint.second];
382 
383  const int row_start = start;
384  const int row_length = task.length_jacobian;
385  const int column_start = (constraint.first - 1) * N; // (t - 1) * N
386  const int column_length = N;
387 
388  const Eigen::MatrixXd jacobian = equality.rho[constraint.first](task.id) * equality.jacobian[constraint.first].middleRows(task.start_jacobian, task.length_jacobian);
389  int row_idx = 0;
390  for (int row = row_start; row < row_start + row_length; ++row)
391  {
392  int column_idx = 0;
393  for (int column = column_start; column < column_start + column_length; ++column)
394  {
395  triplet_list.emplace_back(Eigen::Triplet<double>(row, column, jacobian(row_idx, column_idx)));
396  ++column_idx;
397  }
398  ++row_idx;
399  }
400 
401  start += task.length_jacobian;
402  }
403  return triplet_list;
404 }
405 
406 Eigen::VectorXd AbstractTimeIndexedProblem::GetEquality(int t) const
407 {
409  return equality.S[t] * equality.ydiff[t];
410 }
411 
413 {
415  return equality.S[t] * equality.jacobian[t];
416 }
417 
419 {
420  Eigen::VectorXd neq = Eigen::VectorXd::Zero(active_nonlinear_inequality_constraints_dimension_);
421  int start = 0;
422  for (const auto& constraint : active_nonlinear_inequality_constraints_)
423  {
424  // First is timestep, second is task id
425  const TaskIndexing task = inequality.indexing[constraint.second];
426  neq.segment(start, task.length_jacobian) = inequality.rho[constraint.first](task.id) * inequality.ydiff[constraint.first].segment(task.start_jacobian, task.length_jacobian);
427  start += task.length_jacobian;
428  }
429 
430  return neq;
431 }
432 
433 Eigen::SparseMatrix<double> AbstractTimeIndexedProblem::GetInequalityJacobian() const
434 {
435  Eigen::SparseMatrix<double> jac(active_nonlinear_inequality_constraints_dimension_, N * (T_ - 1));
436  std::vector<Eigen::Triplet<double>> triplet_list = GetInequalityJacobianTriplets();
437  jac.setFromTriplets(triplet_list.begin(), triplet_list.end());
438  return jac;
439 }
440 
441 std::vector<Eigen::Triplet<double>> AbstractTimeIndexedProblem::GetInequalityJacobianTriplets() const
442 {
443  typedef Eigen::Triplet<double> T;
444  std::vector<T> triplet_list;
446  int start = 0;
447  for (const auto& constraint : active_nonlinear_inequality_constraints_)
448  {
449  // First is timestep, second is task id
450  const TaskIndexing task = inequality.indexing[constraint.second];
451 
452  const int row_start = start;
453  const int row_length = task.length_jacobian;
454  const int column_start = (constraint.first - 1) * N; // (t - 1) * N
455  const int column_length = N;
456 
457  const Eigen::MatrixXd jacobian = inequality.rho[constraint.first](task.id) * inequality.jacobian[constraint.first].middleRows(task.start_jacobian, task.length_jacobian);
458  int row_idx = 0;
459  for (int row = row_start; row < row_start + row_length; ++row)
460  {
461  int column_idx = 0;
462  for (int column = column_start; column < column_start + column_length; ++column)
463  {
464  triplet_list.emplace_back(Eigen::Triplet<double>(row, column, jacobian(row_idx, column_idx)));
465  ++column_idx;
466  }
467  ++row_idx;
468  }
469 
470  start += task.length_jacobian;
471  }
472  return triplet_list;
473 }
474 
475 Eigen::VectorXd AbstractTimeIndexedProblem::GetInequality(int t) const
476 {
478  return inequality.S[t] * inequality.ydiff[t];
479 }
480 
482 {
484  return inequality.S[t] * inequality.jacobian[t];
485 }
486 
488 {
490 }
491 
493 {
494  return q_dot_max_;
495 }
496 
497 void AbstractTimeIndexedProblem::SetJointVelocityLimits(const Eigen::VectorXd& qdot_max_in)
498 {
499  if (qdot_max_in.size() == N)
500  {
501  q_dot_max_ = qdot_max_in;
502  }
503  else if (qdot_max_in.size() == 1)
504  {
505  q_dot_max_ = qdot_max_in(0) * Eigen::VectorXd::Ones(N);
506  }
507  else
508  {
509  ThrowPretty("Received size " << qdot_max_in.size() << " but expected 1 or " << N);
510  }
512 }
513 
515 {
516  Eigen::VectorXd g(joint_velocity_constraint_dimension_);
517  for (int t = 1; t < T_; ++t)
518  {
519  g.segment((t - 1) * N, N) = xdiff[t];
520  }
521  return g;
522 }
523 
525 {
526  Eigen::MatrixXd b(joint_velocity_constraint_dimension_, 2);
527  for (int t = 1; t < T_; ++t)
528  {
529  // As we are not including the T=0 in the optimization problem, we cannot
530  // define a transition (xdiff) constraint for the 0th-to-1st timestep
531  // directly - we need to include the constant x_{t=0} values in the ``b``
532  // element of the linear constraint, i.e., as an additional offset in bounds.
533  if (t == 1)
534  {
535  b.block((t - 1) * N, 0, N, 1) = -xdiff_max_ + initial_trajectory_[0];
536  b.block((t - 1) * N, 1, N, 1) = xdiff_max_ + initial_trajectory_[0];
537  }
538  else
539  {
540  b.block((t - 1) * N, 0, N, 1) = -xdiff_max_;
541  b.block((t - 1) * N, 1, N, 1) = xdiff_max_;
542  }
543  }
544  return b;
545 }
546 
548 {
549  // The Jacobian is constant - and thus cached (in ReinitializeVariables)
551 }
552 
553 void AbstractTimeIndexedProblem::SetGoal(const std::string& task_name, Eigen::VectorXdRefConst goal, int t)
554 {
555  cost.SetGoal(task_name, goal, t);
556 }
557 
558 void AbstractTimeIndexedProblem::SetRho(const std::string& task_name, const double rho, int t)
559 {
560  cost.SetRho(task_name, rho, t);
561  PreUpdate();
562 }
563 
564 Eigen::VectorXd AbstractTimeIndexedProblem::GetGoal(const std::string& task_name, int t)
565 {
566  return cost.GetGoal(task_name, t);
567 }
568 
569 double AbstractTimeIndexedProblem::GetRho(const std::string& task_name, int t)
570 {
571  return cost.GetRho(task_name, t);
572 }
573 
574 void AbstractTimeIndexedProblem::SetGoalEQ(const std::string& task_name, Eigen::VectorXdRefConst goal, int t)
575 {
576  equality.SetGoal(task_name, goal, t);
577 }
578 
579 void AbstractTimeIndexedProblem::SetRhoEQ(const std::string& task_name, const double rho, int t)
580 {
581  equality.SetRho(task_name, rho, t);
582  PreUpdate();
583 }
584 
585 Eigen::VectorXd AbstractTimeIndexedProblem::GetGoalEQ(const std::string& task_name, int t)
586 {
587  return equality.GetGoal(task_name, t);
588 }
589 
590 double AbstractTimeIndexedProblem::GetRhoEQ(const std::string& task_name, int t)
591 {
592  return equality.GetRho(task_name, t);
593 }
594 
595 void AbstractTimeIndexedProblem::SetGoalNEQ(const std::string& task_name, Eigen::VectorXdRefConst goal, int t)
596 {
597  inequality.SetGoal(task_name, goal, t);
598 }
599 
600 void AbstractTimeIndexedProblem::SetRhoNEQ(const std::string& task_name, const double rho, int t)
601 {
602  inequality.SetRho(task_name, rho, t);
603  PreUpdate();
604 }
605 
606 Eigen::VectorXd AbstractTimeIndexedProblem::GetGoalNEQ(const std::string& task_name, int t)
607 {
608  return inequality.GetGoal(task_name, t);
609 }
610 
611 double AbstractTimeIndexedProblem::GetRhoNEQ(const std::string& task_name, int t)
612 {
613  return inequality.GetRho(task_name, t);
614 }
615 } // namespace exotica
exotica::TaskIndexing::id
int id
Definition: tasks.h:48
exotica::KIN_H
@ KIN_H
Definition: kinematic_tree.h:61
exotica::PlanningProblem::number_of_problem_updates_
unsigned int number_of_problem_updates_
Definition: planning_problem.h:111
exotica::AbstractTimeIndexedProblem::cost_Phi
TaskSpaceVector cost_Phi
Definition: abstract_time_indexed_problem.h:265
exotica::TimeIndexedTask::ReinitializeVariables
void ReinitializeVariables(int _T, std::shared_ptr< PlanningProblem > _prob, const TaskSpaceVector &_Phi)
Definition: tasks.cpp:420
exotica::AbstractTimeIndexedProblem::initial_trajectory_
std::vector< Eigen::VectorXd > initial_trajectory_
Definition: abstract_time_indexed_problem.h:269
exotica::AppendVector
void AppendVector(std::vector< Val > &orig, const std::vector< Val > &extra)
Definition: conversions.h:223
exotica::AbstractTimeIndexedProblem::SetGoalNEQ
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
Sets goal for a given task at a given timestep (inequality task).
Definition: abstract_time_indexed_problem.cpp:595
exotica::AbstractTimeIndexedProblem::get_active_nonlinear_inequality_constraints_dimension
int get_active_nonlinear_inequality_constraints_dimension() const
Returns the dimension of the active inequality constraints.
Definition: abstract_time_indexed_problem.cpp:344
exotica::AbstractTimeIndexedProblem::GetJointVelocityConstraintBounds
Eigen::MatrixXd GetJointVelocityConstraintBounds() const
Returns the joint velocity constraint bounds (constant terms).
Definition: abstract_time_indexed_problem.cpp:524
exotica::AbstractTimeIndexedProblem::active_nonlinear_inequality_constraints_
std::vector< std::pair< int, int > > active_nonlinear_inequality_constraints_
Definition: abstract_time_indexed_problem.h:279
exotica::PlanningProblem::flags_
KinematicRequestFlags flags_
Definition: planning_problem.h:109
exotica::AbstractTimeIndexedProblem::GetT
int GetT() const
Returns the number of timesteps in the trajectory.
Definition: abstract_time_indexed_problem.cpp:112
exotica::PlanningProblem::SetStartState
void SetStartState(Eigen::VectorXdRefConst x)
Definition: planning_problem.cpp:91
exotica::AbstractTimeIndexedProblem::GetScalarTransitionCost
double GetScalarTransitionCost(int t) const
Returns the scalar transition cost (x^T*W*x) at timestep t.
Definition: abstract_time_indexed_problem.cpp:327
exotica::AbstractTimeIndexedProblem::joint_velocity_constraint_dimension_
int joint_velocity_constraint_dimension_
Definition: abstract_time_indexed_problem.h:284
exotica::AbstractTimeIndexedProblem::x
std::vector< Eigen::VectorXd > x
Current internal problem state.
Definition: abstract_time_indexed_problem.h:260
exotica::AbstractTimeIndexedProblem::GetDuration
double GetDuration() const
Returns the duration of the trajectory (T * tau).
Definition: abstract_time_indexed_problem.cpp:199
exotica::AbstractTimeIndexedProblem::SetTau
void SetTau(const double tau_in)
Sets the time discretization tau for the trajectory.
Definition: abstract_time_indexed_problem.cpp:132
exotica::AbstractTimeIndexedProblem::GetGoalEQ
Eigen::VectorXd GetGoalEQ(const std::string &task_name, int t=0)
Returns the goal for a given task at a given timestep (equality task).
Definition: abstract_time_indexed_problem.cpp:585
exotica::TimeIndexedTask::Update
void Update(const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_dPhi_dx, Eigen::MatrixXdRefConst big_dPhi_du, HessianRefConst big_ddPhi_ddx, HessianRefConst big_ddPhi_ddu, HessianRefConst big_ddPhi_dxdu, int t)
Definition: tasks.cpp:261
exotica::KIN_J
@ KIN_J
Definition: kinematic_tree.h:59
exotica::AbstractTimeIndexedProblem::GetEquality
Eigen::VectorXd GetEquality() const
Returns the equality constraint values for the entire trajectory.
Definition: abstract_time_indexed_problem.cpp:349
generate_initializers.n
n
Definition: generate_initializers.py:628
exotica::AbstractTimeIndexedProblem::jacobian
std::vector< Eigen::MatrixXd > jacobian
Definition: abstract_time_indexed_problem.h:232
exotica::AbstractTimeIndexedProblem::ValidateTimeIndex
void ValidateTimeIndex(int &t_in) const
Checks the desired time index for bounds and supports -1 indexing.
Definition: abstract_time_indexed_problem.h:245
exotica::AbstractTimeIndexedProblem::Update
void Update(Eigen::VectorXdRefConst x_trajectory_in)
Updates the entire problem from a given trajectory (e.g., used in an optimization solver)
Definition: abstract_time_indexed_problem.cpp:204
exotica::AbstractTimeIndexedProblem::GetGoal
Eigen::VectorXd GetGoal(const std::string &task_name, int t=0)
Returns the goal for a given task at a given timestep (cost task).
Definition: abstract_time_indexed_problem.cpp:564
exotica::PlanningProblem::UpdateMultipleTaskKinematics
void UpdateMultipleTaskKinematics(std::vector< std::shared_ptr< KinematicResponse >> responses)
Definition: planning_problem.cpp:240
exotica::AbstractTimeIndexedProblem::SetGoal
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
Sets goal for a given task at a given timestep (cost task).
Definition: abstract_time_indexed_problem.cpp:553
exotica::PlanningProblem::N
int N
Definition: planning_problem.h:97
exotica::TimeIndexedTask::SetGoal
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal, int t)
Definition: tasks.cpp:337
exotica
Definition: collision_scene.h:46
exotica::TaskIndexing::start_jacobian
int start_jacobian
Definition: tasks.h:51
exotica::Hessian
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
Definition: conversions.h:154
exotica::AbstractTimeIndexedProblem::GetScalarTaskCost
double GetScalarTaskCost(int t) const
Returns the scalar task cost at timestep t.
Definition: abstract_time_indexed_problem.cpp:315
exotica::TimeIndexedTask::SetRho
void SetRho(const std::string &task_name, const double rho_in, int t)
Definition: tasks.cpp:365
exotica::PlanningProblem::tasks_
TaskMapVec tasks_
Definition: planning_problem.h:108
exotica::AbstractTimeIndexedProblem::GetEqualityJacobianTriplets
std::vector< Eigen::Triplet< double > > GetEqualityJacobianTriplets() const
Returns a vector of triplets to fill a sparse Jacobian for the equality constraints.
Definition: abstract_time_indexed_problem.cpp:372
exotica::AbstractTimeIndexedProblem::GetJointVelocityConstraint
Eigen::VectorXd GetJointVelocityConstraint() const
Returns the joint velocity constraint inequality terms (linear).
Definition: abstract_time_indexed_problem.cpp:514
exotica::AbstractTimeIndexedProblem::GetRhoEQ
double GetRhoEQ(const std::string &task_name, int t=0)
Returns the precision (Rho) for a given task at a given timestep (equality task).
Definition: abstract_time_indexed_problem.cpp:590
exotica::AbstractTimeIndexedProblem::GetInitialTrajectory
std::vector< Eigen::VectorXd > GetInitialTrajectory() const
Returns the initial trajectory/seed.
Definition: abstract_time_indexed_problem.cpp:194
exotica::AbstractTimeIndexedProblem::equality_Phi
TaskSpaceVector equality_Phi
Definition: abstract_time_indexed_problem.h:267
exotica::AbstractTimeIndexedProblem::GetJointVelocityLimits
Eigen::VectorXd GetJointVelocityLimits() const
Returns the per-DoF joint velocity limit vector.
Definition: abstract_time_indexed_problem.cpp:492
HIGHLIGHT_NAMED
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
exotica::KIN_FK
@ KIN_FK
Definition: kinematic_tree.h:58
exotica::AbstractTimeIndexedProblem::PreUpdate
virtual void PreUpdate()
Updates internal variables before solving, e.g., after setting new values for Rho.
Definition: abstract_time_indexed_problem.cpp:139
exotica::PlanningProblem::scene_
ScenePtr scene_
Definition: planning_problem.h:106
exotica::AbstractTimeIndexedProblem::T_
int T_
Number of time steps.
Definition: abstract_time_indexed_problem.h:257
exotica::AbstractTimeIndexedProblem::xdiff_max_
Eigen::VectorXd xdiff_max_
Maximum change in the variables in a single timestep tau_. Gets set/updated via SetJointVelocityLimit...
Definition: abstract_time_indexed_problem.h:275
exotica::AbstractTimeIndexedProblem::SetRhoEQ
void SetRhoEQ(const std::string &task_name, const double rho, int t=0)
Sets Rho for a given task at a given timestep (equality task).
Definition: abstract_time_indexed_problem.cpp:579
exotica::AbstractTimeIndexedProblem::SetT
void SetT(const int T_in)
Sets the number of timesteps in the trajectory. Note: Rho/Goal need to be updated for every timestep ...
Definition: abstract_time_indexed_problem.cpp:117
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
exotica::AbstractTimeIndexedProblem::ReinitializeVariables
virtual void ReinitializeVariables()
Definition: abstract_time_indexed_problem.cpp:47
exotica::AbstractTimeIndexedProblem::tau_
double tau_
Time step duration.
Definition: abstract_time_indexed_problem.h:258
exotica::TaskSpaceVector
Definition: task_space_vector.h:50
exotica::AbstractTimeIndexedProblem::GetInequalityJacobian
Eigen::SparseMatrix< double > GetInequalityJacobian() const
Returns the sparse Jacobian matrix of the inequality constraints over the entire trajectory.
Definition: abstract_time_indexed_problem.cpp:433
exotica::AbstractTimeIndexedProblem::hessian
std::vector< Hessian > hessian
Definition: abstract_time_indexed_problem.h:233
exotica::AbstractTimeIndexedProblem::SetJointVelocityLimits
void SetJointVelocityLimits(const Eigen::VectorXd &qdot_max_in)
Sets the joint velocity limits. Supports N- and 1-dimensional vectors.
Definition: abstract_time_indexed_problem.cpp:497
exotica::AbstractTimeIndexedProblem::SetRho
void SetRho(const std::string &task_name, const double rho, int t=0)
Sets Rho for a given task at a given timestep (cost task).
Definition: abstract_time_indexed_problem.cpp:558
Eigen::MatrixXdRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
exotica::AbstractTimeIndexedProblem::num_tasks
int num_tasks
Definition: abstract_time_indexed_problem.h:238
exotica::Object::debug_
bool debug_
Definition: object.h:86
exotica::AbstractTimeIndexedProblem::equality
TimeIndexedTask equality
General equality task.
Definition: abstract_time_indexed_problem.h:226
exotica::TaskSpaceVector::map
std::vector< TaskVectorEntry > map
Definition: task_space_vector.h:59
exotica::AbstractTimeIndexedProblem::length_jacobian
int length_jacobian
Definition: abstract_time_indexed_problem.h:237
exotica::AbstractTimeIndexedProblem::GetGoalNEQ
Eigen::VectorXd GetGoalNEQ(const std::string &task_name, int t=0)
Returns the goal for a given task at a given timestep (goal task).
Definition: abstract_time_indexed_problem.cpp:606
exotica::TimeIndexedTask::GetGoal
Eigen::VectorXd GetGoal(const std::string &task_name, int t) const
Definition: tasks.cpp:352
exotica::AbstractTimeIndexedProblem::cost
TimeIndexedTask cost
Cost task.
Definition: abstract_time_indexed_problem.h:224
exotica::AbstractTimeIndexedProblem::~AbstractTimeIndexedProblem
virtual ~AbstractTimeIndexedProblem()
exotica::Task::indexing
std::vector< TaskIndexing > indexing
Definition: tasks.h:64
exotica::AbstractTimeIndexedProblem::Phi
std::vector< TaskSpaceVector > Phi
Definition: abstract_time_indexed_problem.h:231
exotica::AbstractTimeIndexedProblem::get_joint_velocity_constraint_dimension
int get_joint_velocity_constraint_dimension() const
Returns the dimension of the joint velocity constraint (linear inequality).
Definition: abstract_time_indexed_problem.cpp:487
abstract_time_indexed_problem.h
exotica::AbstractTimeIndexedProblem::GetCost
double GetCost() const
Returns the scalar cost for the entire trajectory (both task and transition cost).
Definition: abstract_time_indexed_problem.cpp:294
exotica::AbstractTimeIndexedProblem::get_ct
double get_ct() const
Returns the cost scaling factor.
Definition: abstract_time_indexed_problem.cpp:289
exotica::AbstractTimeIndexedProblem::active_nonlinear_inequality_constraints_dimension_
int active_nonlinear_inequality_constraints_dimension_
Definition: abstract_time_indexed_problem.h:281
exotica::TimeIndexedTask::GetRho
double GetRho(const std::string &task_name, int t) const
Definition: tasks.cpp:380
exotica::AbstractTimeIndexedProblem::GetJointVelocityConstraintJacobianTriplets
std::vector< Eigen::Triplet< double > > GetJointVelocityConstraintJacobianTriplets() const
Returns the joint velocity constraint Jacobian as triplets.
Definition: abstract_time_indexed_problem.cpp:547
start
ROSCPP_DECL void start()
exotica::TimeIndexedTask::rho
std::vector< Eigen::VectorXd > rho
Definition: tasks.h:112
exotica::TimeIndexedTask::jacobian
std::vector< Eigen::MatrixXd > jacobian
Definition: tasks.h:120
exotica::AbstractTimeIndexedProblem::GetScalarTaskJacobian
Eigen::RowVectorXd GetScalarTaskJacobian(int t) const
Returns the Jacobian of the scalar task cost at timestep t.
Definition: abstract_time_indexed_problem.cpp:321
setup.h
exotica::TaskIndexing::length_jacobian
int length_jacobian
Definition: tasks.h:52
exotica::TimeIndexedTask::S
std::vector< Eigen::MatrixXd > S
Definition: tasks.h:123
exotica::AbstractTimeIndexedProblem::GetRho
double GetRho(const std::string &task_name, int t=0)
Returns the precision (Rho) for a given task at a given timestep (cost task).
Definition: abstract_time_indexed_problem.cpp:569
exotica::AbstractTimeIndexedProblem::SetInitialTrajectory
void SetInitialTrajectory(const std::vector< Eigen::VectorXd > &q_init_in)
Sets the initial trajectory/seed.
Definition: abstract_time_indexed_problem.cpp:181
exotica::TimeIndexedTask::ydiff
std::vector< Eigen::VectorXd > ydiff
Definition: tasks.h:114
exotica::AbstractTimeIndexedProblem::GetBounds
Eigen::MatrixXd GetBounds() const
Returns the joint bounds (first column lower, second column upper).
Definition: abstract_time_indexed_problem.cpp:42
exotica::AbstractTimeIndexedProblem::GetEqualityJacobian
Eigen::SparseMatrix< double > GetEqualityJacobian() const
Returns the sparse Jacobian matrix of the equality constraints over the entire trajectory.
Definition: abstract_time_indexed_problem.cpp:364
exotica::AbstractTimeIndexedProblem::active_nonlinear_equality_constraints_
std::vector< std::pair< int, int > > active_nonlinear_equality_constraints_
Definition: abstract_time_indexed_problem.h:278
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
exotica::AbstractTimeIndexedProblem::xdiff
std::vector< Eigen::VectorXd > xdiff
Definition: abstract_time_indexed_problem.h:261
exotica::AbstractTimeIndexedProblem::SetRhoNEQ
void SetRhoNEQ(const std::string &task_name, const double rho, int t=0)
Sets Rho for a given task at a given timestep (inequality task).
Definition: abstract_time_indexed_problem.cpp:600
exotica::AbstractTimeIndexedProblem::GetCostJacobian
Eigen::RowVectorXd GetCostJacobian() const
Returns the Jacobian of the scalar cost over the entire trajectory (Jacobian of GetCost).
Definition: abstract_time_indexed_problem.cpp:304
exotica::TimeIndexedTask::UpdateS
void UpdateS()
Definition: tasks.cpp:246
exotica::AbstractTimeIndexedProblem::q_dot_max_
Eigen::VectorXd q_dot_max_
Joint velocity limit (rad/s)
Definition: abstract_time_indexed_problem.h:274
exotica::AbstractTimeIndexedProblem::kinematic_solutions_
std::vector< std::shared_ptr< KinematicResponse > > kinematic_solutions_
Definition: abstract_time_indexed_problem.h:270
exotica::AbstractTimeIndexedProblem::SetGoalEQ
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
Sets goal for a given task at a given timestep (equality task).
Definition: abstract_time_indexed_problem.cpp:574
exotica::AbstractTimeIndexedProblem::inequality
TimeIndexedTask inequality
General inequality task.
Definition: abstract_time_indexed_problem.h:225
exotica::AbstractTimeIndexedProblem::inequality_Phi
TaskSpaceVector inequality_Phi
Definition: abstract_time_indexed_problem.h:266
exotica::AbstractTimeIndexedProblem::GetTau
double GetTau() const
Returns the time discretization tau for the trajectory.
Definition: abstract_time_indexed_problem.cpp:127
exotica::AbstractTimeIndexedProblem::AbstractTimeIndexedProblem
AbstractTimeIndexedProblem()
Definition: abstract_time_indexed_problem.cpp:35
exotica::PlanningProblem::PreUpdate
virtual void PreUpdate()
Definition: planning_problem.cpp:86
exotica::AbstractTimeIndexedProblem::length_Phi
int length_Phi
Definition: abstract_time_indexed_problem.h:236
exotica::AbstractTimeIndexedProblem::GetInequalityJacobianTriplets
std::vector< Eigen::Triplet< double > > GetInequalityJacobianTriplets() const
Returns a vector of triplets to fill a sparse Jacobian for the inequality constraints.
Definition: abstract_time_indexed_problem.cpp:441
exotica::AbstractTimeIndexedProblem::get_active_nonlinear_equality_constraints_dimension
int get_active_nonlinear_equality_constraints_dimension() const
Returns the dimension of the active equality constraints.
Definition: abstract_time_indexed_problem.cpp:339
exotica::AbstractTimeIndexedProblem::joint_velocity_constraint_jacobian_triplets_
std::vector< Eigen::Triplet< double > > joint_velocity_constraint_jacobian_triplets_
Definition: abstract_time_indexed_problem.h:285
exotica::AbstractTimeIndexedProblem::GetScalarTransitionJacobian
Eigen::RowVectorXd GetScalarTransitionJacobian(int t) const
Returns the Jacobian of the transition cost at timestep t.
Definition: abstract_time_indexed_problem.cpp:333
exotica::AbstractTimeIndexedProblem::W
Eigen::MatrixXd W
Definition: abstract_time_indexed_problem.h:228
exotica::AbstractTimeIndexedProblem::GetRhoNEQ
double GetRhoNEQ(const std::string &task_name, int t=0)
Returns the precision (Rho) for a given task at a given timestep (equality task).
Definition: abstract_time_indexed_problem.cpp:611
exotica::AbstractTimeIndexedProblem::GetInequality
Eigen::VectorXd GetInequality() const
Returns the inequality constraint values for the entire trajectory.
Definition: abstract_time_indexed_problem.cpp:418
exotica::AbstractTimeIndexedProblem::ct
double ct
Normalisation of scalar cost and Jacobian over trajectory length.
Definition: abstract_time_indexed_problem.h:272
t
geometry_msgs::TransformStamped t
exotica::TaskIndexing
Definition: tasks.h:46
exotica::TaskSpaceVector::SetZero
void SetZero(const int n)
Definition: task_space_vector.cpp:54
ThrowNamed
#define ThrowNamed(m)
Definition: exception.h:42
exotica::AbstractTimeIndexedProblem::active_nonlinear_equality_constraints_dimension_
int active_nonlinear_equality_constraints_dimension_
Definition: abstract_time_indexed_problem.h:280


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Oct 20 2023 02:59:49