planning_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 
30 #include <algorithm>
31 #include <limits>
32 #include <utility>
33 
35 #include <exotica_core/server.h>
36 #include <exotica_core/setup.h>
37 
38 #include <exotica_core/planning_problem_initializer.h>
39 #include <exotica_core/task_map_initializer.h>
40 
41 namespace exotica
42 {
45 
46 std::string PlanningProblem::Print(const std::string& prepend) const
47 {
48  std::string ret = Object::Print(prepend);
49  ret += "\n" + prepend + " Task definitions:";
50  for (const auto& it : task_maps_)
51  ret += "\n" + it.second->Print(prepend + " ");
52  return ret;
53 }
54 
56 {
57  return scene_->get_num_positions();
58 }
59 
61 {
62  return scene_->get_num_velocities();
63 }
64 
66 {
67  return scene_->get_num_controls();
68 }
69 
70 Eigen::VectorXd PlanningProblem::ApplyStartState(bool update_traj)
71 {
72  // If we have a scene with a dynamics solver, get position from there
73  if (scene_->GetDynamicsSolver() != nullptr)
74  {
75  const Eigen::VectorXd start_state = scene_->GetDynamicsSolver()->GetPosition(start_state_);
76  scene_->SetModelState(start_state, t_start, update_traj);
77  }
78  else
79  {
80  scene_->SetModelState(start_state_.head(scene_->get_num_positions()), t_start, update_traj);
81  }
82 
83  return scene_->GetControlledState();
84 }
85 
87 {
88  for (auto& it : task_maps_) it.second->PreUpdate();
89 }
90 
92 {
93  // NB: start_state_ has the size nq+nv
94  const auto num_states = scene_->get_num_positions() + scene_->get_num_velocities();
95  // Case 1: The start state encapsulates the full state (nq+nv for dynamic, nq for kinematic)
96  if (x.rows() == num_states)
97  {
98  start_state_ = x;
99  }
100  // Case 2: The start state specifies the state only for the subset of the controlled joint group
101  else if (x.rows() == scene_->GetKinematicTree().GetNumControlledJoints())
102  {
103  auto jointNames = scene_->GetControlledJointNames();
104  auto modelNames = scene_->GetModelJointNames();
105  if (modelNames.size() > start_state_.rows())
106  {
107  std::cout << "start_state_ size: " << start_state_.size() << "\n";
108  std::cout << "jointNames size: " << jointNames.size() << "\n";
109  std::cout << "modelNames size: " << modelNames.size() << "\n";
110  ThrowPretty("Ill-defined condition in PlanningProblem::SetStartState - throwing to avoid illegal memory access (broken logic)!");
111  }
112 
113  for (int i = 0; i < jointNames.size(); ++i)
114  {
115  for (int j = 0; j < modelNames.size(); ++j)
116  {
117  if (jointNames[i] == modelNames[j]) start_state_[j] = x(i);
118  }
119  }
120  }
121  // Case 3: The start state gives only the configuration (nq)
122  else if (x.rows() == scene_->get_num_positions())
123  {
124  start_state_.head(scene_->get_num_positions()) = x;
125  }
126  // TODO: Add support for num_controlled + tangent vector size initialisation
127  else
128  {
129  ThrowNamed("Wrong start state vector size, expected " << num_states << ", got " << x.rows());
130  }
131 }
132 
133 Eigen::VectorXd PlanningProblem::GetStartState() const
134 {
135  return start_state_;
136 }
137 
139 {
140  t_start = t;
141 }
142 
144 {
145  return t_start;
146 }
147 
149 {
150  Object::InstantiateObject(init_in);
151  PlanningProblemInitializer init(init_in);
152 
153  task_maps_.clear();
154  tasks_.clear();
155 
156  // Create the scene
157  scene_.reset(new Scene());
158  scene_->InstantiateInternal(SceneInitializer(init.PlanningScene));
159 
160  // Set size of positions. This is valid for kinematic problems and will be
161  // overridden in dynamic problems inside the Scene.
162  // TODO: "N" should be determined by the Scene or size of the StateVector.
163  N = scene_->GetKinematicTree().GetNumControlledJoints();
164 
165  // Set the start state
166  start_state_ = Eigen::VectorXd::Zero(scene_->get_num_positions() + scene_->get_num_velocities());
167  if (init.StartState.rows() > 0)
168  SetStartState(init.StartState);
169 
170  // Check if the start state needs to be normalised due to a quaternion
171  if (scene_->GetDynamicsSolver() != nullptr &&
172  scene_->GetKinematicTree().GetModelBaseType() == BaseType::FLOATING &&
173  scene_->GetDynamicsSolver()->get_num_state() == scene_->GetDynamicsSolver()->get_num_state_derivative() + 1)
174  {
176  }
177 
178  // Set the start time
179  if (init.StartTime < 0) ThrowNamed("Invalid start time " << init.StartTime);
180  t_start = init.StartTime;
181 
182  // Set the derivative order for Kinematics
183  switch (init.DerivativeOrder)
184  {
185  case -1:
186  // No change - the derived problems have to set it.
187  break;
188  case 0:
189  flags_ = KIN_FK;
190  break;
191  case 1:
192  flags_ = KIN_FK | KIN_J;
193  break;
194  case 2:
195  flags_ = KIN_FK | KIN_J | KIN_H;
196  break;
197  default:
198  ThrowPretty("Unsupported DerivativeOrder: " << init.DerivativeOrder);
199  }
200 
201  KinematicsRequest request;
202  request.flags = flags_;
203 
204  // Create the maps
205  int id = 0;
206  for (const Initializer& MapInitializer : init.Maps)
207  {
208  TaskMapPtr new_map = Setup::CreateMap(MapInitializer);
209  new_map->AssignScene(scene_);
210  new_map->ns_ = ns_ + "/" + new_map->GetObjectName();
211  if (task_maps_.find(new_map->GetObjectName()) != task_maps_.end())
212  {
213  ThrowNamed("Map '" + new_map->GetObjectName() + "' already exists!");
214  }
215  std::vector<KinematicFrameRequest> frames = new_map->GetFrames();
216 
217  for (size_t i = 0; i < new_map->kinematics.size(); ++i)
218  new_map->kinematics[i] = KinematicSolution(id, frames.size());
219  id += frames.size();
220 
221  request.frames.insert(request.frames.end(), frames.begin(), frames.end());
222  task_maps_[new_map->GetObjectName()] = new_map;
223  tasks_.push_back(new_map);
224  }
225  scene_->RequestKinematics(request, std::bind(&PlanningProblem::UpdateTaskKinematics, this, std::placeholders::_1));
226 
227  id = 0;
228  int idJ = 0;
229  for (int i = 0; i < tasks_.size(); ++i)
230  {
231  tasks_[i]->id = i;
232  tasks_[i]->start = id;
233  tasks_[i]->length = tasks_[i]->TaskSpaceDim();
234  tasks_[i]->start_jacobian = idJ;
235  tasks_[i]->length_jacobian = tasks_[i]->TaskSpaceJacobianDim();
236  id += tasks_[i]->length;
237  idJ += tasks_[i]->length_jacobian;
238  }
239 
240  if (debug_ && init.Maps.size() == 0)
241  {
242  HIGHLIGHT("No maps were defined!");
243  }
244 }
245 
246 void PlanningProblem::UpdateTaskKinematics(std::shared_ptr<KinematicResponse> response)
247 {
248  for (auto task : tasks_)
249  task->kinematics[0].Create(response);
250 }
251 
252 void PlanningProblem::UpdateMultipleTaskKinematics(std::vector<std::shared_ptr<KinematicResponse>> responses)
253 {
254  for (auto task : tasks_)
255  {
256  if (task->kinematics.size() > responses.size())
257  {
258  ThrowNamed(responses.size() << " responses provided but task " << task->GetObjectName() << " requires " << task->kinematics.size());
259  }
260 
261  for (size_t i = 0; i < task->kinematics.size(); ++i)
262  {
263  task->kinematics[i].Create(responses[i]);
264  }
265  }
266 }
267 
269 {
270  return task_maps_;
271 }
272 
274 {
275  return tasks_;
276 }
277 
279 {
280  return scene_;
281 }
282 
283 std::pair<std::vector<double>, std::vector<double>> PlanningProblem::GetCostEvolution() const
284 {
285  std::pair<std::vector<double>, std::vector<double>> ret;
286  for (size_t position = 0; position < cost_evolution_.size(); ++position)
287  {
288  if (std::isnan(cost_evolution_[position].second)) break;
289  double time_point = std::chrono::duration_cast<std::chrono::duration<double>>(cost_evolution_[position].first - cost_evolution_[0].first).count();
290  ret.first.push_back(time_point);
291  ret.second.push_back(cost_evolution_[position].second);
292  }
293  return ret;
294 }
295 
297 {
298  return static_cast<int>(std::get<0>(GetCostEvolution()).size());
299 }
300 
301 double PlanningProblem::GetCostEvolution(int index) const
302 {
303  if (index > -1 && index < cost_evolution_.size())
304  {
305  return cost_evolution_[index].second;
306  }
307  else if (index == -1)
308  {
309  return cost_evolution_[cost_evolution_.size() - 1].second;
310  }
311  else
312  {
313  ThrowPretty("Out of range");
314  }
315 }
316 
318 {
319  cost_evolution_.resize(size);
320  cost_evolution_.assign(size, std::make_pair<std::chrono::high_resolution_clock::time_point, double>(std::chrono::high_resolution_clock::now(), std::numeric_limits<double>::quiet_NaN()));
321 }
322 
323 void PlanningProblem::SetCostEvolution(int index, double value)
324 {
325  if (index > -1 && index < cost_evolution_.size())
326  {
327  cost_evolution_[index].first = std::chrono::high_resolution_clock::now();
328  cost_evolution_[index].second = value;
329  }
330  else if (index == -1)
331  {
332  cost_evolution_[cost_evolution_.size() - 1].first = std::chrono::high_resolution_clock::now();
333  cost_evolution_[cost_evolution_.size() - 1].second = value;
334  }
335  else
336  {
337  ThrowPretty("Out of range: " << index << " where length=" << cost_evolution_.size());
338  }
339 }
340 } // namespace exotica
response
const std::string response
exotica::PlanningProblem::SetCostEvolution
void SetCostEvolution(int index, double value)
Definition: planning_problem.cpp:323
exotica::KIN_H
@ KIN_H
Definition: kinematic_tree.h:61
exotica::Object::InstantiateObject
void InstantiateObject(const Initializer &init)
Definition: object.h:71
exotica::KinematicsRequest::frames
std::vector< KinematicFrameRequest > frames
Definition: kinematic_tree.h:97
exotica::PlanningProblem::SetStartTime
void SetStartTime(double t)
Definition: planning_problem.cpp:138
exotica::PlanningProblem::flags_
KinematicRequestFlags flags_
Definition: planning_problem.h:108
exotica::PlanningProblem::InstantiateBase
void InstantiateBase(const Initializer &init) override
Definition: planning_problem.cpp:148
exotica::TaskMapVec
std::vector< TaskMapPtr > TaskMapVec
Definition: task_map.h:94
exotica::PlanningProblem::t_start
double t_start
Definition: planning_problem.h:110
planning_problem.h
exotica::PlanningProblem::GetTasks
TaskMapVec & GetTasks()
Definition: planning_problem.cpp:273
exotica::PlanningProblem::SetStartState
void SetStartState(Eigen::VectorXdRefConst x)
Definition: planning_problem.cpp:91
exotica::Scene
The class of EXOTica Scene.
Definition: scene.h:69
exotica::PlanningProblem::cost_evolution_
std::vector< std::pair< std::chrono::high_resolution_clock::time_point, double > > cost_evolution_
Definition: planning_problem.h:112
exotica::PlanningProblem::ResetCostEvolution
void ResetCostEvolution(size_t size)
Definition: planning_problem.cpp:317
exotica::NormalizeQuaternionInConfigurationVector
void NormalizeQuaternionInConfigurationVector(Eigen::Ref< Eigen::VectorXd > q)
Definition: conversions.h:142
exotica::KIN_J
@ KIN_J
Definition: kinematic_tree.h:59
exotica::PlanningProblem::get_num_controls
int get_num_controls() const
Definition: planning_problem.cpp:65
exotica::Object::Print
virtual std::string Print(const std::string &prepend) const
Definition: object.h:78
exotica::PlanningProblem::UpdateMultipleTaskKinematics
void UpdateMultipleTaskKinematics(std::vector< std::shared_ptr< KinematicResponse >> responses)
Definition: planning_problem.cpp:252
exotica::PlanningProblem::start_state_
Eigen::VectorXd start_state_
Definition: planning_problem.h:109
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::Object::ns_
std::string ns_
Definition: object.h:84
exotica::PlanningProblem::tasks_
TaskMapVec tasks_
Definition: planning_problem.h:107
exotica::KIN_FK
@ KIN_FK
Definition: kinematic_tree.h:58
exotica::KinematicsRequest::flags
KinematicRequestFlags flags
Definition: kinematic_tree.h:96
exotica::PlanningProblem::scene_
ScenePtr scene_
Definition: planning_problem.h:105
exotica::PlanningProblem::PlanningProblem
PlanningProblem()
exotica::PlanningProblem::Print
std::string Print(const std::string &prepend) const override
Definition: planning_problem.cpp:46
exotica::ScenePtr
std::shared_ptr< Scene > ScenePtr
Definition: scene.h:246
exotica::PlanningProblem::~PlanningProblem
virtual ~PlanningProblem()
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:53
HIGHLIGHT
#define HIGHLIGHT(x)
Definition: printable.h:61
exotica::Object::debug_
bool debug_
Definition: object.h:86
exotica::PlanningProblem::get_num_positions
int get_num_positions() const
! Dimension of planning problem. TODO: Update from positions/velocities/controls and make private.
Definition: planning_problem.cpp:55
exotica::Initializer
Definition: property.h:70
exotica::PlanningProblem::GetStartState
Eigen::VectorXd GetStartState() const
Definition: planning_problem.cpp:133
exotica::PlanningProblem::UpdateTaskKinematics
void UpdateTaskKinematics(std::shared_ptr< KinematicResponse > response)
Definition: planning_problem.cpp:246
exotica::Setup::CreateMap
static std::shared_ptr< exotica::TaskMap > CreateMap(const std::string &type, bool prepend=true)
Definition: setup.h:65
setup.h
exotica::PlanningProblem::GetTaskMaps
TaskMapMap & GetTaskMaps()
Definition: planning_problem.cpp:268
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
exotica::PlanningProblem::GetStartTime
double GetStartTime() const
Definition: planning_problem.cpp:143
exotica::PlanningProblem::GetNumberOfIterations
int GetNumberOfIterations() const
Definition: planning_problem.cpp:296
exotica::PlanningProblem::task_maps_
TaskMapMap task_maps_
Definition: planning_problem.h:106
exotica::TaskMapMap
std::map< std::string, TaskMapPtr > TaskMapMap
The mapping by name of TaskMaps.
Definition: task_map.h:93
exotica::KinematicsRequest
Definition: kinematic_tree.h:93
exotica::PlanningProblem::ApplyStartState
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
Definition: planning_problem.cpp:70
index
unsigned int index
init
void init(const M_string &remappings)
x
double x
exotica::PlanningProblem::get_num_velocities
int get_num_velocities() const
Definition: planning_problem.cpp:60
exotica::PlanningProblem::PreUpdate
virtual void PreUpdate()
Definition: planning_problem.cpp:86
exotica::TaskMapPtr
std::shared_ptr< TaskMap > TaskMapPtr
Task Map smart pointer.
Definition: task_map.h:92
exotica::PlanningProblem::GetCostEvolution
std::pair< std::vector< double >, std::vector< double > > GetCostEvolution() const
Definition: planning_problem.cpp:283
server.h
exotica::PlanningProblem::GetScene
ScenePtr GetScene() const
Definition: planning_problem.cpp:278
t
geometry_msgs::TransformStamped t
ThrowNamed
#define ThrowNamed(m)
Definition: exception.h:42
exotica::KinematicSolution
The KinematicSolution is created from - and maps into - a KinematicResponse.
Definition: kinematic_tree.h:127


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