time_indexed_sampling_problem.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
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 
34 
35 namespace exotica
36 {
38 {
39  flags_ = KIN_FK;
40 }
41 
43 
45 {
46  std::vector<double> bounds;
47  auto joint_limits = scene_->GetKinematicTree().GetJointLimits();
48 
49  bounds.resize(2 * N);
50  for (unsigned int i = 0; i < N; ++i)
51  {
52  bounds[i] = joint_limits(i, 0);
53  bounds[i + N] = joint_limits(i, 1);
54  }
55 
56  return bounds;
57 }
58 
59 void TimeIndexedSamplingProblem::Instantiate(const TimeIndexedSamplingProblemInitializer& init)
60 {
61  parameters = init;
62 
63  if (init.Goal.size() == N)
64  {
65  goal_ = init.Goal;
66  }
67  else if (init.Goal.size() == 0)
68  {
69  goal_ = Eigen::VectorXd::Zero(N);
70  }
71  else
72  {
73  ThrowNamed("Dimension mismatch: problem N=" << N << ", but goal state has dimension " << goal_.rows());
74  }
75 
76  t_goal_ = init.GoalTime;
77  if (t_goal_ <= t_start)
78  ThrowNamed("Invalid goal time t_goal= " << t_goal_ << ", where t_start=" << t_start);
79 
80  // Deprecated signature, retained right now for backwards compatibility
81  if (init.JointVelocityLimits.size() != 0)
82  {
83  WARNING("The JointVelocityLimits initialiser is deprecated - use JointVelocityLimits in the Scene initialiser!");
84  Eigen::VectorXd velocity_limits(N);
85  if (init.JointVelocityLimits.size() == N)
86  {
87  velocity_limits = init.JointVelocityLimits;
88  }
89  else if (init.JointVelocityLimits.size() == 1)
90  {
91  velocity_limits = init.JointVelocityLimits(0) * Eigen::VectorXd::Ones(N);
92  }
93  else
94  {
95  ThrowNamed("Dimension mismatch: problem N=" << N << ", but joint velocity limits has dimension " << init.JointVelocityLimits.rows());
96  }
97  scene_->GetKinematicTree().SetJointVelocityLimits(velocity_limits);
98  }
99 
100  if (debug_)
101  {
102  auto vel_limits = scene_->GetKinematicTree().GetVelocityLimits();
103  HIGHLIGHT_NAMED("TimeIndexedSamplingProblem::Instantiate", "Joint velocity limits: " << vel_limits.transpose());
104  }
105 
106  num_tasks = tasks_.size();
107  length_Phi = 0;
108  length_jacobian = 0;
109  for (int i = 0; i < num_tasks; ++i)
110  {
111  AppendVector(Phi.map, tasks_[i]->GetLieGroupIndices());
112  length_Phi += tasks_[i]->length;
113  length_jacobian += tasks_[i]->length_jacobian;
114  }
116 
117  inequality.Initialize(init.Inequality, shared_from_this(), constraint_phi);
118  inequality.tolerance = init.ConstraintTolerance;
119  equality.Initialize(init.Equality, shared_from_this(), constraint_phi);
120  equality.tolerance = init.ConstraintTolerance;
121 
122  ApplyStartState(false);
123 
124  if (scene_->GetKinematicTree().GetControlledBaseType() != exotica::BaseType::FIXED && init.FloatingBaseLowerLimits.rows() > 0 && init.FloatingBaseUpperLimits.rows() > 0)
125  {
126  if (scene_->GetKinematicTree().GetControlledBaseType() == exotica::BaseType::FLOATING && init.FloatingBaseLowerLimits.rows() == 6 && init.FloatingBaseUpperLimits.rows() == 6)
127  {
128  scene_->GetKinematicTree().SetFloatingBaseLimitsPosXYZEulerZYX(
129  std::vector<double>(init.FloatingBaseLowerLimits.data(), init.FloatingBaseLowerLimits.data() + init.FloatingBaseLowerLimits.size()),
130  std::vector<double>(init.FloatingBaseUpperLimits.data(), init.FloatingBaseUpperLimits.data() + init.FloatingBaseUpperLimits.size()));
131  }
132  else if (scene_->GetKinematicTree().GetControlledBaseType() == exotica::BaseType::PLANAR && init.FloatingBaseLowerLimits.rows() == 3 && init.FloatingBaseUpperLimits.rows() == 3)
133  {
134  scene_->GetKinematicTree().SetPlanarBaseLimitsPosXYEulerZ(
135  std::vector<double>(init.FloatingBaseLowerLimits.data(), init.FloatingBaseLowerLimits.data() + init.FloatingBaseLowerLimits.size()),
136  std::vector<double>(init.FloatingBaseUpperLimits.data(), init.FloatingBaseUpperLimits.data() + init.FloatingBaseUpperLimits.size()));
137  }
138  else
139  {
140  ThrowNamed("Invalid base limits!");
141  }
142  }
143 
144  PreUpdate();
145 }
146 
148 {
149  return t_goal_;
150 }
151 
153 {
154  t_goal_ = t;
155 }
156 
158 {
159  return goal_;
160 }
161 
163 {
164  if (qT.rows() != N)
165  ThrowPretty("Dimensionality of goal state wrong: Got " << qT.rows() << ", expected " << N);
166  goal_ = qT;
167 }
168 
169 void TimeIndexedSamplingProblem::SetGoalEQ(const std::string& task_name, Eigen::VectorXdRefConst goal)
170 {
171  for (int i = 0; i < equality.indexing.size(); ++i)
172  {
173  if (equality.tasks[i]->GetObjectName() == task_name)
174  {
175  if (goal.rows() != equality.indexing[i].length) ThrowPretty("Expected length of " << equality.indexing[i].length << " and got " << goal.rows());
176  equality.y.data.segment(equality.indexing[i].start, equality.indexing[i].length) = goal;
177  return;
178  }
179  }
180  ThrowPretty("Cannot set Goal. Task map '" << task_name << "' does not exist.");
181 }
182 
183 void TimeIndexedSamplingProblem::SetRhoEQ(const std::string& task_name, const double& rho)
184 {
185  for (int i = 0; i < equality.indexing.size(); ++i)
186  {
187  if (equality.tasks[i]->GetObjectName() == task_name)
188  {
189  equality.rho(equality.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 TimeIndexedSamplingProblem::GetGoalEQ(const std::string& task_name)
198 {
199  for (int i = 0; i < equality.indexing.size(); ++i)
200  {
201  if (equality.tasks[i]->GetObjectName() == task_name)
202  {
203  return equality.y.data.segment(equality.indexing[i].start, equality.indexing[i].length);
204  }
205  }
206  ThrowPretty("Cannot get Goal. Task map '" << task_name << "' does not exist.");
207 }
208 
209 double TimeIndexedSamplingProblem::GetRhoEQ(const std::string& task_name)
210 {
211  for (int i = 0; i < equality.indexing.size(); ++i)
212  {
213  if (equality.tasks[i]->GetObjectName() == task_name)
214  {
215  return equality.rho(equality.indexing[i].id);
216  }
217  }
218  ThrowPretty("Cannot get rho. Task map '" << task_name << "' does not exist.");
219 }
220 
221 void TimeIndexedSamplingProblem::SetGoalNEQ(const std::string& task_name, Eigen::VectorXdRefConst goal)
222 {
223  for (int i = 0; i < inequality.indexing.size(); ++i)
224  {
225  if (inequality.tasks[i]->GetObjectName() == task_name)
226  {
227  if (goal.rows() != inequality.indexing[i].length) ThrowPretty("Expected length of " << inequality.indexing[i].length << " and got " << goal.rows());
228  inequality.y.data.segment(inequality.indexing[i].start, inequality.indexing[i].length) = goal;
229  return;
230  }
231  }
232  ThrowPretty("Cannot set Goal. Task map '" << task_name << "' does not exist.");
233 }
234 
235 void TimeIndexedSamplingProblem::SetRhoNEQ(const std::string& task_name, const double& rho)
236 {
237  for (int i = 0; i < inequality.indexing.size(); ++i)
238  {
239  if (inequality.tasks[i]->GetObjectName() == task_name)
240  {
241  inequality.rho(inequality.indexing[i].id) = rho;
242  PreUpdate();
243  return;
244  }
245  }
246  ThrowPretty("Cannot set rho. Task map '" << task_name << "' does not exist.");
247 }
248 
249 Eigen::VectorXd TimeIndexedSamplingProblem::GetGoalNEQ(const std::string& task_name)
250 {
251  for (int i = 0; i < inequality.indexing.size(); ++i)
252  {
253  if (inequality.tasks[i]->GetObjectName() == task_name)
254  {
255  return inequality.y.data.segment(inequality.indexing[i].start, inequality.indexing[i].length);
256  }
257  }
258  ThrowPretty("Cannot get Goal. Task map '" << task_name << "' does not exist.");
259 }
260 
261 double TimeIndexedSamplingProblem::GetRhoNEQ(const std::string& task_name)
262 {
263  for (int i = 0; i < inequality.indexing.size(); ++i)
264  {
265  if (inequality.tasks[i]->GetObjectName() == task_name)
266  {
267  return inequality.rho(inequality.indexing[i].id);
268  }
269  }
270  ThrowPretty("Cannot get rho. Task map '" << task_name << "' does not exist.");
271 }
272 
274 {
275  scene_->Update(x, t);
276  for (int i = 0; i < num_tasks; ++i)
277  {
278  if (tasks_[i]->is_used)
279  tasks_[i]->Update(x, Phi.data.segment(tasks_[i]->start, tasks_[i]->length));
280  }
284 
285  bool inequality_is_valid = ((inequality.S * inequality.ydiff).array() <= 0.0).all();
286  bool equality_is_valid = ((equality.S * equality.ydiff).array().abs() == 0.0).all();
287 
288  if (debug_)
289  {
290  HIGHLIGHT_NAMED("TimeIndexedSamplingProblem::IsValid", "Equality valid? = " << equality_is_valid << "\tInequality valid? = " << inequality_is_valid);
291  }
292 
293  return (inequality_is_valid && equality_is_valid);
294 }
295 
297 {
299  for (int i = 0; i < tasks_.size(); ++i) tasks_[i]->is_used = false;
301  equality.UpdateS();
302 }
303 
305 {
306  IsValid(x, t);
308 }
309 
311 {
312  return N;
313 }
314 } // namespace exotica
exotica::PlanningProblem::number_of_problem_updates_
unsigned int number_of_problem_updates_
Definition: planning_problem.h:111
exotica::AppendVector
void AppendVector(std::vector< Val > &orig, const std::vector< Val > &extra)
Definition: conversions.h:224
exotica::TimeIndexedSamplingProblem::inequality
SamplingTask inequality
Definition: time_indexed_sampling_problem.h:74
exotica::TimeIndexedSamplingProblem::TimeIndexedSamplingProblem
TimeIndexedSamplingProblem()
Definition: time_indexed_sampling_problem.cpp:37
exotica::PlanningProblem::flags_
KinematicRequestFlags flags_
Definition: planning_problem.h:108
exotica::PLANAR
@ PLANAR
Definition: kinematic_tree.h:53
exotica::TimeIndexedSamplingProblem::GetSpaceDim
int GetSpaceDim()
Definition: time_indexed_sampling_problem.cpp:310
exotica::TimeIndexedSamplingProblem::t_goal_
double t_goal_
Goal time: The time at which goal_ should be reached and the upper bound for the time-dimension.
Definition: time_indexed_sampling_problem.h:84
exotica::PlanningProblem::t_start
double t_start
Definition: planning_problem.h:110
exotica::SamplingTask::Initialize
virtual void Initialize(const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi)
Definition: tasks.cpp:494
exotica::TimeIndexedSamplingProblem::SetRhoEQ
void SetRhoEQ(const std::string &task_name, const double &rho)
Definition: time_indexed_sampling_problem.cpp:183
exotica::TimeIndexedSamplingProblem::Update
void Update(Eigen::VectorXdRefConst x, const double &t)
Definition: time_indexed_sampling_problem.cpp:304
exotica::TimeIndexedSamplingProblem::GetGoalEQ
Eigen::VectorXd GetGoalEQ(const std::string &task_name)
Definition: time_indexed_sampling_problem.cpp:197
exotica::PlanningProblem::N
int N
Definition: planning_problem.h:96
exotica
Definition: collision_scene.h:46
exotica::FLOATING
@ FLOATING
Definition: kinematic_tree.h:52
exotica::TimeIndexedSamplingProblem::parameters
TimeIndexedSamplingProblemInitializer parameters
Definition: time_indexed_sampling_problem.h:76
exotica::TimeIndexedSamplingProblem::Phi
TaskSpaceVector Phi
Definition: time_indexed_sampling_problem.h:73
exotica::PlanningProblem::tasks_
TaskMapVec tasks_
Definition: planning_problem.h:107
exotica::SamplingTask::rho
Eigen::VectorXd rho
Definition: tasks.h:172
HIGHLIGHT_NAMED
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
exotica::SamplingTask::Update
void Update(const TaskSpaceVector &big_Phi)
Definition: tasks.cpp:545
exotica::KIN_FK
@ KIN_FK
Definition: kinematic_tree.h:58
exotica::TimeIndexedSamplingProblem::constraint_phi
TaskSpaceVector constraint_phi
Definition: time_indexed_sampling_problem.h:77
exotica::TimeIndexedSamplingProblem::GetGoalTime
double GetGoalTime() const
Definition: time_indexed_sampling_problem.cpp:147
exotica::TimeIndexedSamplingProblem::GetGoalNEQ
Eigen::VectorXd GetGoalNEQ(const std::string &task_name)
Definition: time_indexed_sampling_problem.cpp:249
exotica::PlanningProblem::scene_
ScenePtr scene_
Definition: planning_problem.h:105
time_indexed_sampling_problem.h
exotica::TimeIndexedSamplingProblem::SetGoalTime
void SetGoalTime(const double &t)
Definition: time_indexed_sampling_problem.cpp:152
exotica::TimeIndexedSamplingProblem::SetGoalNEQ
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
Definition: time_indexed_sampling_problem.cpp:221
exotica::TimeIndexedSamplingProblem::Instantiate
void Instantiate(const TimeIndexedSamplingProblemInitializer &init) override
Definition: time_indexed_sampling_problem.cpp:59
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:53
exotica::TimeIndexedSamplingProblem::SetGoalState
void SetGoalState(Eigen::VectorXdRefConst qT)
Definition: time_indexed_sampling_problem.cpp:162
REGISTER_PROBLEM_TYPE
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
Definition: planning_problem.h:45
exotica::TimeIndexedSamplingProblem::GetBounds
std::vector< double > GetBounds()
Definition: time_indexed_sampling_problem.cpp:44
exotica::SamplingTask::y
TaskSpaceVector y
Definition: tasks.h:173
exotica::SamplingTask::ydiff
Eigen::VectorXd ydiff
Definition: tasks.h:174
exotica::Object::debug_
bool debug_
Definition: object.h:86
exotica::TaskSpaceVector::map
std::vector< TaskVectorEntry > map
Definition: task_space_vector.h:59
exotica::TimeIndexedSamplingProblem::~TimeIndexedSamplingProblem
virtual ~TimeIndexedSamplingProblem()
exotica::Task::indexing
std::vector< TaskIndexing > indexing
Definition: tasks.h:64
exotica::TimeIndexedSamplingProblem::GetRhoNEQ
double GetRhoNEQ(const std::string &task_name)
Definition: time_indexed_sampling_problem.cpp:261
exotica::TimeIndexedSamplingProblem
Definition: time_indexed_sampling_problem.h:40
exotica::TimeIndexedSamplingProblem::length_Phi
int length_Phi
Definition: time_indexed_sampling_problem.h:79
setup.h
exotica::TimeIndexedSamplingProblem::PreUpdate
void PreUpdate() override
Definition: time_indexed_sampling_problem.cpp:296
exotica::TimeIndexedSamplingProblem::goal_
Eigen::VectorXd goal_
Goal state to reach (spatial) at temporal goal (t_goal_)
Definition: time_indexed_sampling_problem.h:85
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
exotica::Task::tolerance
double tolerance
Definition: tasks.h:69
exotica::TimeIndexedSamplingProblem::SetGoalEQ
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
Definition: time_indexed_sampling_problem.cpp:169
WARNING
#define WARNING(x)
With endline.
Definition: printable.h:56
exotica::PlanningProblem::ApplyStartState
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
Definition: planning_problem.cpp:70
exotica::TimeIndexedSamplingProblem::GetRhoEQ
double GetRhoEQ(const std::string &task_name)
Definition: time_indexed_sampling_problem.cpp:209
exotica::TimeIndexedSamplingProblem::SetRhoNEQ
void SetRhoNEQ(const std::string &task_name, const double &rho)
Definition: time_indexed_sampling_problem.cpp:235
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::FIXED
@ FIXED
Definition: kinematic_tree.h:51
exotica::PlanningProblem::PreUpdate
virtual void PreUpdate()
Definition: planning_problem.cpp:86
exotica::PlanningProblem::IsValid
virtual bool IsValid()
Evaluates whether the problem is valid.
Definition: planning_problem.h:93
exotica::TimeIndexedSamplingProblem::equality
SamplingTask equality
Definition: time_indexed_sampling_problem.h:75
t
geometry_msgs::TransformStamped t
exotica::SamplingTask::UpdateS
void UpdateS()
Definition: tasks.cpp:533
exotica::TimeIndexedSamplingProblem::num_tasks
int num_tasks
Definition: time_indexed_sampling_problem.h:81
exotica::TimeIndexedSamplingProblem::length_jacobian
int length_jacobian
Definition: time_indexed_sampling_problem.h:80
exotica::TimeIndexedSamplingProblem::GetGoalState
Eigen::VectorXd GetGoalState() const
Definition: time_indexed_sampling_problem.cpp:157
exotica::TaskSpaceVector::SetZero
void SetZero(const int n)
Definition: task_space_vector.cpp:54
ThrowNamed
#define ThrowNamed(m)
Definition: exception.h:42
exotica::SamplingTask::S
Eigen::MatrixXd S
Definition: tasks.h:176


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sun Jun 2 2024 02:58:18