end_pose_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 #include <exotica_core/task_initializer.h>
34 
36 
37 namespace exotica
38 {
40 {
41  flags_ = KIN_FK | KIN_J;
42 }
43 
45 
46 Eigen::MatrixXd EndPoseProblem::GetBounds() const
47 {
48  return scene_->GetKinematicTree().GetJointLimits();
49 }
50 
51 void EndPoseProblem::Instantiate(const EndPoseProblemInitializer& init)
52 {
53  parameters_ = init;
54  num_tasks = tasks_.size();
55  length_Phi = 0;
56  length_jacobian = 0;
57  for (int i = 0; i < num_tasks; ++i)
58  {
59  AppendVector(Phi.map, tasks_[i]->GetLieGroupIndices());
60  length_Phi += tasks_[i]->length;
61  length_jacobian += tasks_[i]->length_jacobian;
62  }
64  W = Eigen::MatrixXd::Identity(N, N);
65  if (init.W.rows() > 0)
66  {
67  if (init.W.rows() == N)
68  {
69  W.diagonal() = init.W;
70  }
71  else
72  {
73  ThrowNamed("W dimension mismatch! Expected " << N << ", got " << init.W.rows());
74  }
75  }
76  if (flags_ & KIN_J) jacobian = Eigen::MatrixXd(length_jacobian, N);
77  if (flags_ & KIN_H) hessian.setConstant(length_jacobian, Eigen::MatrixXd::Zero(N, N));
78 
79  if (init.LowerBound.rows() == N)
80  {
81  scene_->GetKinematicTree().SetJointLimitsLower(init.LowerBound);
82  }
83  else if (init.LowerBound.rows() != 0)
84  {
85  ThrowNamed("Lower bound size incorrect! Expected " << N << " got " << init.LowerBound.rows());
86  }
87  if (init.UpperBound.rows() == N)
88  {
89  scene_->GetKinematicTree().SetJointLimitsUpper(init.UpperBound);
90  }
91  else if (init.UpperBound.rows() != 0)
92  {
93  ThrowNamed("Lower bound size incorrect! Expected " << N << " got " << init.UpperBound.rows());
94  }
95 
96  use_bounds = init.UseBounds;
97 
98  TaskSpaceVector dummy;
99  cost.Initialize(init.Cost, shared_from_this(), dummy);
100  inequality.Initialize(init.Inequality, shared_from_this(), dummy);
101  equality.Initialize(init.Equality, shared_from_this(), dummy);
102  ApplyStartState(false);
103  PreUpdate();
104 }
105 
107 {
109  for (int i = 0; i < tasks_.size(); ++i) tasks_[i]->is_used = false;
110  cost.UpdateS();
112  equality.UpdateS();
113 }
114 
116 {
117  return cost.ydiff.transpose() * cost.S * cost.ydiff;
118 }
119 
121 {
122  return cost.jacobian.transpose() * cost.S * cost.ydiff * 2.0;
123 }
124 
125 double EndPoseProblem::GetScalarTaskCost(const std::string& task_name) const
126 {
127  for (int i = 0; i < cost.indexing.size(); ++i)
128  {
129  if (cost.tasks[i]->GetObjectName() == task_name)
130  {
131  return cost.ydiff.segment(cost.indexing[i].start, cost.indexing[i].length).transpose() * cost.rho(cost.indexing[i].id) * cost.ydiff.segment(cost.indexing[i].start, cost.indexing[i].length);
132  }
133  }
134  ThrowPretty("Cannot get scalar task cost. Task Map '" << task_name << "' does not exist.");
135 }
136 
138 {
139  return equality.S * equality.ydiff;
140 }
141 
143 {
144  return equality.S * equality.jacobian;
145 }
146 
148 {
149  return inequality.S * inequality.ydiff;
150 }
151 
153 {
154  return inequality.S * inequality.jacobian;
155 }
156 
158 {
159  scene_->Update(x, t_start);
161  if (flags_ & KIN_J) jacobian.setZero();
162  if (flags_ & KIN_H)
163  for (int i = 0; i < length_jacobian; ++i) hessian(i).setZero();
164  for (int i = 0; i < tasks_.size(); ++i)
165  {
166  if (tasks_[i]->is_used)
167  {
168  if (flags_ & KIN_H)
169  {
170  tasks_[i]->Update(x,
171  Phi.data.segment(tasks_[i]->start, tasks_[i]->length),
172  jacobian.middleRows(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian),
173  hessian.segment(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian));
174  }
175  else if (flags_ & KIN_J)
176  {
177  tasks_[i]->Update(x,
178  Phi.data.segment(tasks_[i]->start, tasks_[i]->length),
179  Eigen::MatrixXdRef(jacobian.middleRows(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian)) // Adding MatrixXdRef(...) is a work-around for issue #737 when using Eigen 3.3.9
180  );
181  }
182  else
183  {
184  tasks_[i]->Update(x, Phi.data.segment(tasks_[i]->start, tasks_[i]->length));
185  }
186  }
187  }
188  if (flags_ & KIN_H)
189  {
193  }
194  else if (flags_ & KIN_J)
195  {
199  }
200  else
201  {
202  cost.Update(Phi);
205  }
207 }
208 
209 void EndPoseProblem::SetGoal(const std::string& task_name, Eigen::VectorXdRefConst goal)
210 {
211  for (int i = 0; i < cost.indexing.size(); ++i)
212  {
213  if (cost.tasks[i]->GetObjectName() == task_name)
214  {
215  if (goal.rows() != cost.indexing[i].length) ThrowPretty("Expected length of " << cost.indexing[i].length << " and got " << goal.rows());
216  cost.y.data.segment(cost.indexing[i].start, cost.indexing[i].length) = goal;
217  return;
218  }
219  }
220  ThrowPretty("Cannot set Goal. Task Map '" << task_name << "' does not exist.");
221 }
222 
223 void EndPoseProblem::SetRho(const std::string& task_name, const double& rho)
224 {
225  for (int i = 0; i < cost.indexing.size(); ++i)
226  {
227  if (cost.tasks[i]->GetObjectName() == task_name)
228  {
229  cost.rho(cost.indexing[i].id) = rho;
230  PreUpdate();
231  return;
232  }
233  }
234  ThrowPretty("Cannot set rho. Task Map '" << task_name << "' does not exist.");
235 }
236 
237 Eigen::VectorXd EndPoseProblem::GetGoal(const std::string& task_name)
238 {
239  for (int i = 0; i < cost.indexing.size(); ++i)
240  {
241  if (cost.tasks[i]->GetObjectName() == task_name)
242  {
243  return cost.y.data.segment(cost.indexing[i].start, cost.indexing[i].length);
244  }
245  }
246  ThrowPretty("Cannot get Goal. Task Map '" << task_name << "' does not exist.");
247 }
248 
249 double EndPoseProblem::GetRho(const std::string& task_name)
250 {
251  for (int i = 0; i < cost.indexing.size(); ++i)
252  {
253  if (cost.tasks[i]->GetObjectName() == task_name)
254  {
255  return cost.rho(cost.indexing[i].id);
256  }
257  }
258  ThrowPretty("Cannot get rho. Task Map '" << task_name << "' does not exist.");
259 }
260 
261 void EndPoseProblem::SetGoalEQ(const std::string& task_name, Eigen::VectorXdRefConst goal)
262 {
263  for (int i = 0; i < equality.indexing.size(); ++i)
264  {
265  if (equality.tasks[i]->GetObjectName() == task_name)
266  {
267  if (goal.rows() != equality.indexing[i].length) ThrowPretty("Expected length of " << equality.indexing[i].length << " and got " << goal.rows());
268  equality.y.data.segment(equality.indexing[i].start, equality.indexing[i].length) = goal;
269  return;
270  }
271  }
272  ThrowPretty("Cannot set Goal. Task Map '" << task_name << "' does not exist.");
273 }
274 
275 void EndPoseProblem::SetRhoEQ(const std::string& task_name, const double& rho)
276 {
277  for (int i = 0; i < equality.indexing.size(); ++i)
278  {
279  if (equality.tasks[i]->GetObjectName() == task_name)
280  {
281  equality.rho(equality.indexing[i].id) = rho;
282  PreUpdate();
283  return;
284  }
285  }
286  ThrowPretty("Cannot set rho. Task Map '" << task_name << "' does not exist.");
287 }
288 
289 Eigen::VectorXd EndPoseProblem::GetGoalEQ(const std::string& task_name)
290 {
291  for (int i = 0; i < equality.indexing.size(); ++i)
292  {
293  if (equality.tasks[i]->GetObjectName() == task_name)
294  {
295  return equality.y.data.segment(equality.indexing[i].start, equality.indexing[i].length);
296  }
297  }
298  ThrowPretty("Cannot get Goal. Task Map '" << task_name << "' does not exist.");
299 }
300 
301 double EndPoseProblem::GetRhoEQ(const std::string& task_name)
302 {
303  for (int i = 0; i < equality.indexing.size(); ++i)
304  {
305  if (equality.tasks[i]->GetObjectName() == task_name)
306  {
307  return equality.rho(equality.indexing[i].id);
308  }
309  }
310  ThrowPretty("Cannot get rho. Task Map '" << task_name << "' does not exist.");
311 }
312 
313 void EndPoseProblem::SetGoalNEQ(const std::string& task_name, Eigen::VectorXdRefConst goal)
314 {
315  for (int i = 0; i < inequality.indexing.size(); ++i)
316  {
317  if (inequality.tasks[i]->GetObjectName() == task_name)
318  {
319  if (goal.rows() != inequality.indexing[i].length) ThrowPretty("Expected length of " << inequality.indexing[i].length << " and got " << goal.rows());
320  inequality.y.data.segment(inequality.indexing[i].start, inequality.indexing[i].length) = goal;
321  return;
322  }
323  }
324  ThrowPretty("Cannot set Goal. Task Map '" << task_name << "' does not exist.");
325 }
326 
327 void EndPoseProblem::SetRhoNEQ(const std::string& task_name, const double& rho)
328 {
329  for (int i = 0; i < inequality.indexing.size(); ++i)
330  {
331  if (inequality.tasks[i]->GetObjectName() == task_name)
332  {
333  inequality.rho(inequality.indexing[i].id) = rho;
334  PreUpdate();
335  return;
336  }
337  }
338  ThrowPretty("Cannot set rho. Task Map '" << task_name << "' does not exist.");
339 }
340 
341 Eigen::VectorXd EndPoseProblem::GetGoalNEQ(const std::string& task_name)
342 {
343  for (int i = 0; i < inequality.indexing.size(); ++i)
344  {
345  if (inequality.tasks[i]->GetObjectName() == task_name)
346  {
347  return inequality.y.data.segment(inequality.indexing[i].start, inequality.indexing[i].length);
348  }
349  }
350  ThrowPretty("Cannot get Goal. Task Map '" << task_name << "' does not exist.");
351 }
352 
353 double EndPoseProblem::GetRhoNEQ(const std::string& task_name)
354 {
355  for (int i = 0; i < inequality.indexing.size(); ++i)
356  {
357  if (inequality.tasks[i]->GetObjectName() == task_name)
358  {
359  return inequality.rho(inequality.indexing[i].id);
360  }
361  }
362  ThrowPretty("Cannot get rho. Task Map '" << task_name << "' does not exist.");
363 }
364 
366 {
367  std::cout.precision(4);
368  bool succeeded = true;
369 
370  if (use_bounds)
371  {
372  Eigen::VectorXd x = scene_->GetKinematicTree().GetControlledState();
373  auto bounds = scene_->GetKinematicTree().GetJointLimits();
374 
375  // Check joint limits
376  constexpr double tolerance = 1.e-3;
377  for (unsigned int i = 0; i < N; ++i)
378  {
379  if (x(i) < bounds(i, 0) - tolerance || x(i) > bounds(i, 1) + tolerance)
380  {
381  if (debug_) HIGHLIGHT_NAMED("EndPoseProblem::IsValid", "Out of bounds (joint #" << i << "): " << bounds(i, 0) << " < " << x(i) << " < " << bounds(i, 1));
382  succeeded = false;
383  }
384  }
385  }
386 
387  // Check inequality constraints
388  if (GetInequality().rows() > 0)
389  {
390  if (GetInequality().maxCoeff() > parameters_.InequalityFeasibilityTolerance)
391  {
392  if (debug_) HIGHLIGHT_NAMED("EndPoseProblem::IsValid", "Violated inequality constraints: " << GetInequality().transpose());
393  succeeded = false;
394  }
395  }
396 
397  // Check equality constraints
398  if (GetEquality().rows() > 0)
399  {
400  if (GetEquality().cwiseAbs().maxCoeff() > parameters_.EqualityFeasibilityTolerance)
401  {
402  if (debug_) HIGHLIGHT_NAMED("EndPoseProblem::IsValid", "Violated equality constraints: " << GetEquality().cwiseAbs().maxCoeff());
403  succeeded = false;
404  }
405  }
406 
407  return succeeded;
408 }
409 } // namespace exotica
std::vector< TaskVectorEntry > map
KinematicRequestFlags flags_
Eigen::MatrixXd S
Definition: tasks.h:154
Eigen::MatrixXd jacobian
Definition: tasks.h:152
Arbitrarily constrained end-pose problem implementation.
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
unsigned int number_of_problem_updates_
Eigen::VectorXd ydiff
Definition: tasks.h:150
Eigen::VectorXd rho
Definition: tasks.h:148
Eigen::MatrixXd GetInequalityJacobian()
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
#define ThrowPretty(m)
Definition: exception.h:36
virtual void Initialize(const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi)
Definition: tasks.cpp:68
Eigen::VectorXd GetInequality()
TaskSpaceVector y
Definition: tasks.h:149
double GetRho(const std::string &task_name)
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
void Update(Eigen::VectorXdRefConst x)
Eigen::MatrixXd jacobian
#define ThrowNamed(m)
Definition: exception.h:42
Eigen::VectorXd GetGoalEQ(const std::string &task_name)
bool debug_
Definition: object.h:86
void SetRhoNEQ(const std::string &task_name, const double &rho)
void SetRhoEQ(const std::string &task_name, const double &rho)
Eigen::VectorXd GetGoal(const std::string &task_name)
Eigen::RowVectorXd GetScalarJacobian()
double GetRhoEQ(const std::string &task_name)
void SetRho(const std::string &task_name, const double &rho)
Eigen::MatrixXd GetBounds() const
Eigen::MatrixXd GetEqualityJacobian()
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
void Instantiate(const EndPoseProblemInitializer &init) override
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
double GetScalarTaskCost(const std::string &task_name) const
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
double GetRhoNEQ(const std::string &task_name)
Eigen::VectorXd GetEquality()
std::vector< TaskIndexing > indexing
Definition: tasks.h:64
void Update(const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_jacobian, HessianRefConst big_hessian)
Definition: tasks.cpp:121
bool IsValid() override
Evaluates whether the problem is valid.
void AppendVector(std::vector< Val > &orig, const std::vector< Val > &extra)
Definition: conversions.h:223
double x
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
TaskMapVec tasks
Definition: tasks.h:63
Eigen::VectorXd GetGoalNEQ(const std::string &task_name)
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Mon Feb 28 2022 22:24:13