unconstrained_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 REGISTER_PROBLEM_TYPE("UnconstrainedEndPoseProblem", exotica::UnconstrainedEndPoseProblem)
34 
35 namespace exotica
36 {
38 {
39  flags_ = KIN_FK | KIN_J;
40 }
41 
43 
44 void UnconstrainedEndPoseProblem::Instantiate(const UnconstrainedEndPoseProblemInitializer& init)
45 {
46  num_tasks = tasks_.size();
47  length_Phi = 0;
48  length_jacobian = 0;
49  for (int i = 0; i < num_tasks; ++i)
50  {
51  AppendVector(Phi.map, tasks_[i]->GetLieGroupIndices());
52  length_Phi += tasks_[i]->length;
53  length_jacobian += tasks_[i]->length_jacobian;
54  }
56  W = Eigen::MatrixXd::Identity(N, N);
57  if (init.W.rows() > 0)
58  {
59  if (init.W.rows() == N)
60  {
61  W.diagonal() = init.W;
62  }
63  else
64  {
65  ThrowNamed("W dimension mismatch! Expected " << N << ", got " << init.W.rows());
66  }
67  }
68  if (flags_ & KIN_J) jacobian = Eigen::MatrixXd(length_jacobian, N);
69  if (flags_ & KIN_H) hessian.setConstant(length_jacobian, Eigen::MatrixXd::Zero(N, N));
70 
71  if (init.NominalState.rows() > 0 && init.NominalState.rows() != N) ThrowNamed("Invalid size of NominalState (" << init.NominalState.rows() << "), expected: " << N);
72  if (init.NominalState.rows() == N) q_nominal = init.NominalState;
73  TaskSpaceVector dummy;
74  cost.Initialize(init.Cost, shared_from_this(), dummy);
75  ApplyStartState(false);
76  PreUpdate();
77 }
78 
80 {
82  for (int i = 0; i < tasks_.size(); ++i) tasks_[i]->is_used = false;
83  cost.UpdateS();
84 }
85 
87 {
88  return cost.ydiff.transpose() * cost.S * cost.ydiff;
89 }
90 
92 {
93  return cost.jacobian.transpose() * cost.S * cost.ydiff * 2.0;
94 }
95 
97 {
98  Eigen::MatrixXd general_cost_hessian = Eigen::MatrixXd::Zero(N, N);
99 
100  // Contract task-map Hessian
101  if (flags_ & KIN_H)
102  {
103  Eigen::RowVectorXd ydiffTS = cost.ydiff.transpose() * cost.S; // (1*m)
104  for (int i = 0; i < cost.length_jacobian; ++i) // length m
105  {
106  general_cost_hessian.noalias() += ydiffTS(i) * cost.hessian(i);
107  }
108  }
109  else
110  {
111  std::cerr << "[UnconstrainedEndPoseProblem::GetHessian] Hessian requested but DerivativeOrder < 2" << std::endl;
112  }
113 
114  return 2. * general_cost_hessian;
115 }
116 
117 double UnconstrainedEndPoseProblem::GetScalarTaskCost(const std::string& task_name) const
118 {
119  const Eigen::VectorXd ydiff = cost.GetTaskError(task_name);
120  return ydiff.transpose() * GetRho(task_name) * ydiff;
121 }
122 
124 {
125  scene_->Update(x, t_start);
127  if (flags_ & KIN_J) jacobian.setZero();
128  if (flags_ & KIN_H)
129  for (int i = 0; i < length_jacobian; ++i) hessian(i).setZero();
130  for (int i = 0; i < tasks_.size(); ++i)
131  {
132  if (tasks_[i]->is_used)
133  {
134  if (flags_ & KIN_H)
135  {
136  tasks_[i]->Update(x,
137  Phi.data.segment(tasks_[i]->start, tasks_[i]->length),
138  jacobian.middleRows(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian),
139  hessian.segment(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian));
140  }
141  else if (flags_ & KIN_J)
142  {
143  tasks_[i]->Update(x,
144  Phi.data.segment(tasks_[i]->start, tasks_[i]->length),
145  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
146  );
147  }
148  else
149  {
150  tasks_[i]->Update(x, Phi.data.segment(tasks_[i]->start, tasks_[i]->length));
151  }
152  }
153  }
154  if (flags_ & KIN_H)
155  {
157  }
158  else if (flags_ & KIN_J)
159  {
161  }
162  else
163  {
164  cost.Update(Phi);
165  }
167 }
168 
169 void UnconstrainedEndPoseProblem::SetGoal(const std::string& task_name, Eigen::VectorXdRefConst goal)
170 {
171  for (int i = 0; i < cost.indexing.size(); ++i)
172  {
173  if (cost.tasks[i]->GetObjectName() == task_name)
174  {
175  if (goal.rows() != cost.indexing[i].length) ThrowPretty("Expected length of " << cost.indexing[i].length << " and got " << goal.rows());
176  cost.y.data.segment(cost.indexing[i].start, cost.indexing[i].length) = goal;
177  return;
178  }
179  }
180  ThrowPretty("Cannot set Goal. Task map '" << task_name << "' does not exist.");
181 }
182 
183 void UnconstrainedEndPoseProblem::SetRho(const std::string& task_name, const double& rho)
184 {
185  for (int i = 0; i < cost.indexing.size(); ++i)
186  {
187  if (cost.tasks[i]->GetObjectName() == task_name)
188  {
189  cost.rho(cost.indexing[i].id) = rho;
190  PreUpdate();
191  return;
192  }
193  }
194  ThrowPretty("Cannot set rho. Task map '" << task_name << "' does not exist.");
195 }
196 
197 Eigen::VectorXd UnconstrainedEndPoseProblem::GetGoal(const std::string& task_name) const
198 {
199  for (int i = 0; i < cost.indexing.size(); ++i)
200  {
201  if (cost.tasks[i]->GetObjectName() == task_name)
202  {
203  return cost.y.data.segment(cost.indexing[i].start, cost.indexing[i].length);
204  }
205  }
206  ThrowPretty("Cannot get Goal. Task map '" << task_name << "' does not exist.");
207 }
208 
209 double UnconstrainedEndPoseProblem::GetRho(const std::string& task_name) const
210 {
211  for (int i = 0; i < cost.indexing.size(); ++i)
212  {
213  if (cost.tasks[i]->GetObjectName() == task_name)
214  {
215  return cost.rho(cost.indexing[i].id);
216  }
217  }
218  ThrowPretty("Cannot get rho. Task map '" << task_name << "' does not exist.");
219 }
220 
222 {
223  return q_nominal;
224 }
225 
227 {
228  if (qNominal_in.rows() == N)
229  q_nominal = qNominal_in;
230  else
231  ThrowPretty("Cannot set q_nominal - wrong number of rows (expected "
232  << N << ", received " << qNominal_in.rows() << ").");
233 }
234 
235 int UnconstrainedEndPoseProblem::GetTaskId(const std::string& task_name) const
236 {
237  for (int i = 0; i < cost.indexing.size(); ++i)
238  {
239  if (cost.tasks[i]->GetObjectName() == task_name)
240  {
241  return i;
242  }
243  }
244  ThrowPretty("Cannot get task. Task map '" << task_name << "' does not exist.");
245 }
246 } // namespace exotica
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::UnconstrainedEndPoseProblem::SetNominalPose
void SetNominalPose(Eigen::VectorXdRefConst qNominal_in)
Definition: unconstrained_end_pose_problem.cpp:226
exotica::EndPoseTask::Update
void Update(const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_jacobian, HessianRefConst big_hessian)
Definition: tasks.cpp:121
exotica::AppendVector
void AppendVector(std::vector< Val > &orig, const std::vector< Val > &extra)
Definition: conversions.h:223
exotica::UnconstrainedEndPoseProblem
Definition: unconstrained_end_pose_problem.h:40
exotica::EndPoseTask::rho
Eigen::VectorXd rho
Definition: tasks.h:148
exotica::UnconstrainedEndPoseProblem::PreUpdate
void PreUpdate() override
Definition: unconstrained_end_pose_problem.cpp:79
exotica::PlanningProblem::flags_
KinematicRequestFlags flags_
Definition: planning_problem.h:109
exotica::EndPoseTask::S
Eigen::MatrixXd S
Definition: tasks.h:154
exotica::UnconstrainedEndPoseProblem::Update
void Update(Eigen::VectorXdRefConst x)
Definition: unconstrained_end_pose_problem.cpp:123
exotica::EndPoseTask::hessian
Hessian hessian
Definition: tasks.h:153
exotica::PlanningProblem::t_start
double t_start
Definition: planning_problem.h:93
exotica::Task::length_jacobian
int length_jacobian
Definition: tasks.h:67
exotica::KIN_J
@ KIN_J
Definition: kinematic_tree.h:59
exotica::EndPoseTask::jacobian
Eigen::MatrixXd jacobian
Definition: tasks.h:152
exotica::UnconstrainedEndPoseProblem::SetGoal
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
Definition: unconstrained_end_pose_problem.cpp:169
exotica::UnconstrainedEndPoseProblem::GetScalarJacobian
Eigen::RowVectorXd GetScalarJacobian() const
Definition: unconstrained_end_pose_problem.cpp:91
unconstrained_end_pose_problem.h
exotica::EndPoseTask::UpdateS
void UpdateS()
Definition: tasks.cpp:109
exotica::PlanningProblem::N
int N
Definition: planning_problem.h:97
exotica
Definition: collision_scene.h:46
exotica::UnconstrainedEndPoseProblem::num_tasks
int num_tasks
Definition: unconstrained_end_pose_problem.h:80
exotica::PlanningProblem::tasks_
TaskMapVec tasks_
Definition: planning_problem.h:108
exotica::EndPoseTask::y
TaskSpaceVector y
Definition: tasks.h:149
exotica::UnconstrainedEndPoseProblem::~UnconstrainedEndPoseProblem
virtual ~UnconstrainedEndPoseProblem()
exotica::KIN_FK
@ KIN_FK
Definition: kinematic_tree.h:58
exotica::PlanningProblem::scene_
ScenePtr scene_
Definition: planning_problem.h:106
exotica::EndPoseTask::Initialize
virtual void Initialize(const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi)
Definition: tasks.cpp:68
exotica::UnconstrainedEndPoseProblem::GetScalarCost
double GetScalarCost() const
Definition: unconstrained_end_pose_problem.cpp:86
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
exotica::UnconstrainedEndPoseProblem::length_jacobian
int length_jacobian
Definition: unconstrained_end_pose_problem.h:79
REGISTER_PROBLEM_TYPE
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
Definition: planning_problem.h:45
exotica::UnconstrainedEndPoseProblem::jacobian
Eigen::MatrixXd jacobian
Definition: unconstrained_end_pose_problem.h:74
exotica::TaskSpaceVector
Definition: task_space_vector.h:50
exotica::UnconstrainedEndPoseProblem::q_nominal
Eigen::VectorXd q_nominal
Definition: unconstrained_end_pose_problem.h:76
exotica::EndPoseTask::GetTaskError
Eigen::VectorXd GetTaskError(const std::string &task_name) const
Definition: tasks.cpp:216
Eigen::MatrixXdRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
exotica::UnconstrainedEndPoseProblem::Phi
TaskSpaceVector Phi
Definition: unconstrained_end_pose_problem.h:73
exotica::TaskSpaceVector::map
std::vector< TaskVectorEntry > map
Definition: task_space_vector.h:59
exotica::UnconstrainedEndPoseProblem::GetNominalPose
Eigen::VectorXd GetNominalPose() const
Definition: unconstrained_end_pose_problem.cpp:221
exotica::Task::indexing
std::vector< TaskIndexing > indexing
Definition: tasks.h:64
exotica::UnconstrainedEndPoseProblem::cost
EndPoseTask cost
Definition: unconstrained_end_pose_problem.h:70
exotica::UnconstrainedEndPoseProblem::GetTaskId
int GetTaskId(const std::string &task_name) const
Definition: unconstrained_end_pose_problem.cpp:235
exotica::UnconstrainedEndPoseProblem::length_Phi
int length_Phi
Definition: unconstrained_end_pose_problem.h:78
setup.h
exotica::UnconstrainedEndPoseProblem::Instantiate
void Instantiate(const UnconstrainedEndPoseProblemInitializer &init) override
Definition: unconstrained_end_pose_problem.cpp:44
exotica::UnconstrainedEndPoseProblem::W
Eigen::MatrixXd W
Definition: unconstrained_end_pose_problem.h:72
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
exotica::UnconstrainedEndPoseProblem::UnconstrainedEndPoseProblem
UnconstrainedEndPoseProblem()
Definition: unconstrained_end_pose_problem.cpp:37
exotica::UnconstrainedEndPoseProblem::GetGoal
Eigen::VectorXd GetGoal(const std::string &task_name) const
Definition: unconstrained_end_pose_problem.cpp:197
exotica::PlanningProblem::ApplyStartState
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
Definition: planning_problem.cpp:70
exotica::Task::tasks
TaskMapVec tasks
Definition: tasks.h:63
init
void init(const M_string &remappings)
exotica::TaskSpaceVector::data
Eigen::VectorXd data
Definition: task_space_vector.h:58
x
double x
exotica::UnconstrainedEndPoseProblem::GetHessian
Eigen::MatrixXd GetHessian() const
Definition: unconstrained_end_pose_problem.cpp:96
exotica::UnconstrainedEndPoseProblem::GetRho
double GetRho(const std::string &task_name) const
Definition: unconstrained_end_pose_problem.cpp:209
exotica::PlanningProblem::PreUpdate
virtual void PreUpdate()
Definition: planning_problem.cpp:86
exotica::UnconstrainedEndPoseProblem::hessian
Hessian hessian
Definition: unconstrained_end_pose_problem.h:75
exotica::UnconstrainedEndPoseProblem::GetScalarTaskCost
double GetScalarTaskCost(const std::string &task_name) const
GetScalarTaskCost get weighted sum-of-squares of cost vector.
Definition: unconstrained_end_pose_problem.cpp:117
exotica::EndPoseTask::ydiff
Eigen::VectorXd ydiff
Definition: tasks.h:150
exotica::TaskSpaceVector::SetZero
void SetZero(const int n)
Definition: task_space_vector.cpp:54
ThrowNamed
#define ThrowNamed(m)
Definition: exception.h:42
exotica::UnconstrainedEndPoseProblem::SetRho
void SetRho(const std::string &task_name, const double &rho)
Definition: unconstrained_end_pose_problem.cpp:183


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