bounded_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 BoundedEndPoseProblem::GetBounds() const
47 {
48  return scene_->GetKinematicTree().GetJointLimits();
49 }
50 
51 void BoundedEndPoseProblem::Instantiate(const BoundedEndPoseProblemInitializer& init)
52 {
53  num_tasks = tasks_.size();
54  length_Phi = 0;
55  length_jacobian = 0;
56  for (int i = 0; i < num_tasks; ++i)
57  {
58  AppendVector(Phi.map, tasks_[i]->GetLieGroupIndices());
59  length_Phi += tasks_[i]->length;
60  length_jacobian += tasks_[i]->length_jacobian;
61  }
63  W = Eigen::MatrixXd::Identity(N, N);
64  if (init.W.rows() > 0)
65  {
66  if (init.W.rows() == N)
67  {
68  W.diagonal() = init.W;
69  }
70  else
71  {
72  ThrowNamed("W dimension mismatch! Expected " << N << ", got " << init.W.rows());
73  }
74  }
75  if (flags_ & KIN_J) jacobian = Eigen::MatrixXd(length_jacobian, N);
76  if (flags_ & KIN_H) hessian.setConstant(length_jacobian, Eigen::MatrixXd::Zero(N, N));
77 
78  if (init.LowerBound.rows() == N)
79  {
80  scene_->GetKinematicTree().SetJointLimitsLower(init.LowerBound);
81  }
82  else if (init.LowerBound.rows() != 0)
83  {
84  ThrowNamed("Lower bound size incorrect! Expected " << N << " got " << init.LowerBound.rows());
85  }
86  if (init.UpperBound.rows() == N)
87  {
88  scene_->GetKinematicTree().SetJointLimitsUpper(init.UpperBound);
89  }
90  else if (init.UpperBound.rows() != 0)
91  {
92  ThrowNamed("Lower bound size incorrect! Expected " << N << " got " << init.UpperBound.rows());
93  }
94 
95  TaskSpaceVector dummy;
96  cost.Initialize(init.Cost, shared_from_this(), dummy);
97  ApplyStartState(false);
98  PreUpdate();
99 }
100 
102 {
104  for (int i = 0; i < tasks_.size(); ++i) tasks_[i]->is_used = false;
105  cost.UpdateS();
106 }
107 
109 {
110  return cost.ydiff.transpose() * cost.S * cost.ydiff;
111 }
112 
114 {
115  return cost.jacobian.transpose() * cost.S * cost.ydiff * 2.0;
116 }
117 
118 double BoundedEndPoseProblem::GetScalarTaskCost(const std::string& task_name) const
119 {
120  for (int i = 0; i < cost.indexing.size(); ++i)
121  {
122  if (cost.tasks[i]->GetObjectName() == task_name)
123  {
124  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);
125  }
126  }
127  ThrowPretty("Cannot get scalar task cost. Task map '" << task_name << "' does not exist.");
128 }
129 
131 {
132  scene_->Update(x, t_start);
134  if (flags_ & KIN_J) jacobian.setZero();
135  if (flags_ & KIN_H)
136  for (int i = 0; i < length_jacobian; ++i) hessian(i).setZero();
137  for (int i = 0; i < tasks_.size(); ++i)
138  {
139  if (tasks_[i]->is_used)
140  {
141  if (flags_ & KIN_H)
142  {
143  tasks_[i]->Update(x,
144  Phi.data.segment(tasks_[i]->start, tasks_[i]->length),
145  jacobian.middleRows(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian),
146  hessian.segment(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian));
147  }
148  else if (flags_ & KIN_J)
149  {
150  tasks_[i]->Update(x,
151  Phi.data.segment(tasks_[i]->start, tasks_[i]->length),
152  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
153  );
154  }
155  else
156  {
157  tasks_[i]->Update(x, Phi.data.segment(tasks_[i]->start, tasks_[i]->length));
158  }
159  }
160  }
161  if (flags_ & KIN_H)
162  {
164  }
165  else if (flags_ & KIN_J)
166  {
168  }
169  else
170  {
171  cost.Update(Phi);
172  }
174 }
175 
176 void BoundedEndPoseProblem::SetGoal(const std::string& task_name, Eigen::VectorXdRefConst goal)
177 {
178  for (int i = 0; i < cost.indexing.size(); ++i)
179  {
180  if (cost.tasks[i]->GetObjectName() == task_name)
181  {
182  if (goal.rows() != cost.indexing[i].length) ThrowPretty("Expected length of " << cost.indexing[i].length << " and got " << goal.rows());
183  cost.y.data.segment(cost.indexing[i].start, cost.indexing[i].length) = goal;
184  return;
185  }
186  }
187  ThrowPretty("Cannot set Goal. Task map '" << task_name << "' does not exist.");
188 }
189 
190 void BoundedEndPoseProblem::SetRho(const std::string& task_name, const double& rho)
191 {
192  for (int i = 0; i < cost.indexing.size(); ++i)
193  {
194  if (cost.tasks[i]->GetObjectName() == task_name)
195  {
196  cost.rho(cost.indexing[i].id) = rho;
197  PreUpdate();
198  return;
199  }
200  }
201  ThrowPretty("Cannot set rho. Task map '" << task_name << "' does not exist.");
202 }
203 
204 Eigen::VectorXd BoundedEndPoseProblem::GetGoal(const std::string& task_name)
205 {
206  for (int i = 0; i < cost.indexing.size(); ++i)
207  {
208  if (cost.tasks[i]->GetObjectName() == task_name)
209  {
210  return cost.y.data.segment(cost.indexing[i].start, cost.indexing[i].length);
211  }
212  }
213  ThrowPretty("Cannot get Goal. Task map '" << task_name << "' does not exist.");
214 }
215 
216 double BoundedEndPoseProblem::GetRho(const std::string& task_name)
217 {
218  for (int i = 0; i < cost.indexing.size(); ++i)
219  {
220  if (cost.tasks[i]->GetObjectName() == task_name)
221  {
222  return cost.rho(cost.indexing[i].id);
223  }
224  }
225  ThrowPretty("Cannot get rho. Task map '" << task_name << "' does not exist.");
226 }
227 
229 {
230  Eigen::VectorXd x = scene_->GetKinematicTree().GetControlledState();
231  Eigen::MatrixXd bounds = scene_->GetKinematicTree().GetJointLimits();
232 
233  std::cout.precision(4);
234  constexpr double tolerance = 1.e-3;
235 
236  bool succeeded = true;
237  for (unsigned int i = 0; i < N; ++i)
238  {
239  if (x(i) < bounds(i, 0) - tolerance || x(i) > bounds(i, 1) + tolerance)
240  {
241  if (debug_) HIGHLIGHT_NAMED("BoundedEndPoseProblem::IsValid", "Out of bounds (joint #" << i << "): " << bounds(i, 0) << " < " << x(i) << " < " << bounds(i, 1));
242  succeeded = false;
243  }
244  }
245  return succeeded;
246 }
247 } // namespace exotica
exotica::BoundedEndPoseProblem::GetScalarTaskCost
double GetScalarTaskCost(const std::string &task_name) const
Definition: bounded_end_pose_problem.cpp:118
exotica::BoundedEndPoseProblem::GetScalarJacobian
Eigen::RowVectorXd GetScalarJacobian() const
Definition: bounded_end_pose_problem.cpp:113
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::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::EndPoseTask::rho
Eigen::VectorXd rho
Definition: tasks.h:148
exotica::PlanningProblem::flags_
KinematicRequestFlags flags_
Definition: planning_problem.h:109
exotica::EndPoseTask::S
Eigen::MatrixXd S
Definition: tasks.h:154
exotica::BoundedEndPoseProblem::GetGoal
Eigen::VectorXd GetGoal(const std::string &task_name)
Definition: bounded_end_pose_problem.cpp:204
exotica::PlanningProblem::t_start
double t_start
Definition: planning_problem.h:93
exotica::BoundedEndPoseProblem::Update
void Update(Eigen::VectorXdRefConst x)
Definition: bounded_end_pose_problem.cpp:130
exotica::BoundedEndPoseProblem::~BoundedEndPoseProblem
virtual ~BoundedEndPoseProblem()
exotica::KIN_J
@ KIN_J
Definition: kinematic_tree.h:59
exotica::EndPoseTask::jacobian
Eigen::MatrixXd jacobian
Definition: tasks.h:152
exotica::BoundedEndPoseProblem::SetGoal
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
Definition: bounded_end_pose_problem.cpp:176
exotica::EndPoseTask::UpdateS
void UpdateS()
Definition: tasks.cpp:109
exotica::PlanningProblem::N
int N
Definition: planning_problem.h:97
exotica::BoundedEndPoseProblem::PreUpdate
void PreUpdate() override
Definition: bounded_end_pose_problem.cpp:101
exotica
Definition: collision_scene.h:46
exotica::PlanningProblem::tasks_
TaskMapVec tasks_
Definition: planning_problem.h:108
exotica::EndPoseTask::y
TaskSpaceVector y
Definition: tasks.h:149
HIGHLIGHT_NAMED
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
exotica::KIN_FK
@ KIN_FK
Definition: kinematic_tree.h:58
exotica::BoundedEndPoseProblem::cost
EndPoseTask cost
Definition: bounded_end_pose_problem.h:63
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::BoundedEndPoseProblem::Phi
TaskSpaceVector Phi
Definition: bounded_end_pose_problem.h:66
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
REGISTER_PROBLEM_TYPE
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
Definition: planning_problem.h:45
exotica::TaskSpaceVector
Definition: task_space_vector.h:50
Eigen::MatrixXdRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
exotica::Object::debug_
bool debug_
Definition: object.h:86
exotica::BoundedEndPoseProblem::length_Phi
int length_Phi
Definition: bounded_end_pose_problem.h:70
exotica::TaskSpaceVector::map
std::vector< TaskVectorEntry > map
Definition: task_space_vector.h:59
exotica::BoundedEndPoseProblem::jacobian
Eigen::MatrixXd jacobian
Definition: bounded_end_pose_problem.h:68
exotica::Task::indexing
std::vector< TaskIndexing > indexing
Definition: tasks.h:64
exotica::BoundedEndPoseProblem::length_jacobian
int length_jacobian
Definition: bounded_end_pose_problem.h:71
bounded_end_pose_problem.h
exotica::BoundedEndPoseProblem::Instantiate
void Instantiate(const BoundedEndPoseProblemInitializer &init) override
Definition: bounded_end_pose_problem.cpp:51
exotica::BoundedEndPoseProblem::W
Eigen::MatrixXd W
Definition: bounded_end_pose_problem.h:65
setup.h
exotica::BoundedEndPoseProblem::IsValid
bool IsValid() override
Evaluates whether the problem is valid.
Definition: bounded_end_pose_problem.cpp:228
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
exotica::BoundedEndPoseProblem::num_tasks
int num_tasks
Definition: bounded_end_pose_problem.h:72
exotica::BoundedEndPoseProblem::GetBounds
Eigen::MatrixXd GetBounds() const
Definition: bounded_end_pose_problem.cpp:46
exotica::BoundedEndPoseProblem::GetRho
double GetRho(const std::string &task_name)
Definition: bounded_end_pose_problem.cpp:216
exotica::PlanningProblem::ApplyStartState
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
Definition: planning_problem.cpp:70
exotica::BoundedEndPoseProblem
Bound constrained end-pose problem implementation.
Definition: bounded_end_pose_problem.h:41
tolerance
S tolerance()
exotica::BoundedEndPoseProblem::SetRho
void SetRho(const std::string &task_name, const double &rho)
Definition: bounded_end_pose_problem.cpp:190
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::PlanningProblem::PreUpdate
virtual void PreUpdate()
Definition: planning_problem.cpp:86
exotica::BoundedEndPoseProblem::GetScalarCost
double GetScalarCost() const
Definition: bounded_end_pose_problem.cpp:108
exotica::BoundedEndPoseProblem::BoundedEndPoseProblem
BoundedEndPoseProblem()
Definition: bounded_end_pose_problem.cpp:39
exotica::BoundedEndPoseProblem::hessian
Hessian hessian
Definition: bounded_end_pose_problem.h:67
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_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Oct 20 2023 02:59:49