unconstrained_time_indexed_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("UnconstrainedTimeIndexedProblem", exotica::UnconstrainedTimeIndexedProblem)
34 
35 namespace exotica
36 {
37 void UnconstrainedTimeIndexedProblem::Instantiate(const UnconstrainedTimeIndexedProblemInitializer& init)
38 {
39  this->parameters_ = init;
40 
41  N = scene_->GetKinematicTree().GetNumControlledJoints();
42 
43  w_scale_ = this->parameters_.Wrate;
44  W = Eigen::MatrixXd::Identity(N, N) * w_scale_;
45  if (this->parameters_.W.rows() > 0)
46  {
47  if (this->parameters_.W.rows() == N)
48  {
49  W.diagonal() = this->parameters_.W * w_scale_;
50  }
51  else
52  {
53  ThrowNamed("W dimension mismatch! Expected " << N << ", got " << this->parameters_.W.rows());
54  }
55  }
56 
57  cost.Initialize(this->parameters_.Cost, shared_from_this(), cost_Phi);
58 
59  T_ = this->parameters_.T;
60  tau_ = this->parameters_.tau;
61  ApplyStartState(false);
63 }
64 
66 {
67  if (debug_) HIGHLIGHT_NAMED("UnconstrainedTimeIndexedProblem", "Initialize problem with T=" << T_);
68 
69  num_tasks = tasks_.size();
70  length_Phi = 0;
71  length_jacobian = 0;
72  TaskSpaceVector y_ref_;
73  for (int i = 0; i < num_tasks; ++i)
74  {
75  AppendVector(y_ref_.map, tasks_[i]->GetLieGroupIndices());
76  length_Phi += tasks_[i]->length;
77  length_jacobian += tasks_[i]->length_jacobian;
78  }
79 
80  y_ref_.SetZero(length_Phi);
81  Phi.assign(T_, y_ref_);
82 
83  x.assign(T_, Eigen::VectorXd::Zero(N));
84  xdiff.assign(T_, Eigen::VectorXd::Zero(N));
85  if (flags_ & KIN_J) jacobian.assign(T_, Eigen::MatrixXd(length_jacobian, N));
86  if (flags_ & KIN_H)
87  {
88  Hessian Htmp;
89  Htmp.setConstant(length_jacobian, Eigen::MatrixXd::Zero(N, N));
90  hessian.assign(T_, Htmp);
91  }
92 
93  // Set initial trajectory with current state
94  initial_trajectory_.resize(T_, scene_->GetControlledState());
95 
96  cost.ReinitializeVariables(T_, shared_from_this(), cost_Phi);
97 
98  // Updates related to tau
99  ct = 1.0 / tau_ / T_;
101 
102  PreUpdate();
103 }
104 
106 {
108  for (int i = 0; i < tasks_.size(); ++i) tasks_[i]->is_used = false;
109  cost.UpdateS();
110 
111  // Create a new set of kinematic solutions with the size of the trajectory
112  // based on the lastest KinematicResponse in order to reflect model state
113  // updates etc.
114  kinematic_solutions_.clear();
115  kinematic_solutions_.resize(T_);
116  for (int i = 0; i < T_; ++i) kinematic_solutions_[i] = std::make_shared<KinematicResponse>(*scene_->GetKinematicTree().GetKinematicResponse());
117 }
118 
120 {
122 
123  x[t] = x_in;
124 
125  // Set the corresponding KinematicResponse for KinematicTree in order to
126  // have Kinematics elements updated based in x_in.
127  scene_->GetKinematicTree().SetKinematicResponse(kinematic_solutions_[t]);
128 
129  // Pass the corresponding number of relevant task kinematics to the TaskMaps
130  // via the PlanningProblem::UpdateMultipleTaskKinematics method. For now we
131  // support passing _two_ timesteps - this can be easily changed later on.
132  std::vector<std::shared_ptr<KinematicResponse>> kinematics_solutions{kinematic_solutions_[t]};
133 
134  // If the current timestep is 0, pass the 0th timestep's response twice.
135  // Otherwise pass the (t-1)th response.
136  kinematics_solutions.emplace_back((t == 0) ? kinematic_solutions_[t] : kinematic_solutions_[t - 1]);
137 
138  // Actually update the tasks' kinematics mappings.
139  PlanningProblem::UpdateMultipleTaskKinematics(kinematics_solutions);
140 
141  scene_->Update(x_in, static_cast<double>(t) * tau_);
142 
143  Phi[t].SetZero(length_Phi);
144  if (flags_ & KIN_J) jacobian[t].setZero();
145  if (flags_ & KIN_H)
146  for (int i = 0; i < length_jacobian; ++i) hessian[t](i).setZero();
147  for (int i = 0; i < num_tasks; ++i)
148  {
149  // Only update TaskMap if rho is not 0
150  if (tasks_[i]->is_used)
151  {
152  if (flags_ & KIN_H)
153  {
154  tasks_[i]->Update(x[t],
155  Phi[t].data.segment(tasks_[i]->start, tasks_[i]->length),
156  jacobian[t].middleRows(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian),
157  hessian[t].segment(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian));
158  }
159  else if (flags_ & KIN_J)
160  {
161  tasks_[i]->Update(x[t],
162  Phi[t].data.segment(tasks_[i]->start, tasks_[i]->length),
163  Eigen::MatrixXdRef(jacobian[t].middleRows(tasks_[i]->start_jacobian, tasks_[i]->length_jacobian)) // Adding MatrixXdRef(...) is a work-around for issue #737 when using Eigen 3.3.9
164  );
165  }
166  else
167  {
168  tasks_[i]->Update(x[t], Phi[t].data.segment(tasks_[i]->start, tasks_[i]->length));
169  }
170  }
171  }
172  if (flags_ & KIN_H)
173  {
174  cost.Update(Phi[t], jacobian[t], hessian[t], t);
175  }
176  else if (flags_ & KIN_J)
177  {
178  cost.Update(Phi[t], jacobian[t], t);
179  }
180  else
181  {
182  cost.Update(Phi[t], t);
183  }
184 
185  if (t > 0) xdiff[t] = x[t] - x[t - 1];
186 
188 }
189 
191 {
192  return true;
193 }
194 } // 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::AbstractTimeIndexedProblem::cost_Phi
TaskSpaceVector cost_Phi
Definition: abstract_time_indexed_problem.h:265
exotica::TimeIndexedTask::ReinitializeVariables
void ReinitializeVariables(int _T, std::shared_ptr< PlanningProblem > _prob, const TaskSpaceVector &_Phi)
Definition: tasks.cpp:420
exotica::AbstractTimeIndexedProblem::initial_trajectory_
std::vector< Eigen::VectorXd > initial_trajectory_
Definition: abstract_time_indexed_problem.h:269
exotica::AppendVector
void AppendVector(std::vector< Val > &orig, const std::vector< Val > &extra)
Definition: conversions.h:223
exotica::Instantiable< UnconstrainedTimeIndexedProblemInitializer >::parameters_
UnconstrainedTimeIndexedProblemInitializer parameters_
Definition: property.h:139
exotica::PlanningProblem::flags_
KinematicRequestFlags flags_
Definition: planning_problem.h:109
exotica::UnconstrainedTimeIndexedProblem::Update
void Update(Eigen::VectorXdRefConst x_in, int t) override
Updates an individual timestep from a given state vector.
Definition: unconstrained_time_indexed_problem.cpp:119
exotica::AbstractTimeIndexedProblem::x
std::vector< Eigen::VectorXd > x
Current internal problem state.
Definition: abstract_time_indexed_problem.h:260
exotica::TimeIndexedTask::Update
void Update(const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_dPhi_dx, Eigen::MatrixXdRefConst big_dPhi_du, HessianRefConst big_ddPhi_ddx, HessianRefConst big_ddPhi_ddu, HessianRefConst big_ddPhi_dxdu, int t)
Definition: tasks.cpp:261
exotica::AbstractTimeIndexedProblem::w_scale_
double w_scale_
Kinematic system transition error covariance multiplier (constant throughout the trajectory)
Definition: abstract_time_indexed_problem.h:263
exotica::KIN_J
@ KIN_J
Definition: kinematic_tree.h:59
exotica::UnconstrainedTimeIndexedProblem::ReinitializeVariables
void ReinitializeVariables() override
Definition: unconstrained_time_indexed_problem.cpp:65
exotica::AbstractTimeIndexedProblem::jacobian
std::vector< Eigen::MatrixXd > jacobian
Definition: abstract_time_indexed_problem.h:232
exotica::AbstractTimeIndexedProblem::ValidateTimeIndex
void ValidateTimeIndex(int &t_in) const
Checks the desired time index for bounds and supports -1 indexing.
Definition: abstract_time_indexed_problem.h:245
exotica::UnconstrainedTimeIndexedProblem::PreUpdate
void PreUpdate() override
Updates internal variables before solving, e.g., after setting new values for Rho.
Definition: unconstrained_time_indexed_problem.cpp:105
exotica::PlanningProblem::UpdateMultipleTaskKinematics
void UpdateMultipleTaskKinematics(std::vector< std::shared_ptr< KinematicResponse >> responses)
Definition: planning_problem.cpp:240
exotica::PlanningProblem::N
int N
Definition: planning_problem.h:97
exotica
Definition: collision_scene.h:46
exotica::Hessian
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
Definition: conversions.h:154
exotica::PlanningProblem::tasks_
TaskMapVec tasks_
Definition: planning_problem.h:108
exotica::UnconstrainedTimeIndexedProblem::IsValid
bool IsValid() override
Evaluates whether the problem is valid.
Definition: unconstrained_time_indexed_problem.cpp:190
HIGHLIGHT_NAMED
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
unconstrained_time_indexed_problem.h
exotica::PlanningProblem::scene_
ScenePtr scene_
Definition: planning_problem.h:106
exotica::AbstractTimeIndexedProblem::T_
int T_
Number of time steps.
Definition: abstract_time_indexed_problem.h:257
exotica::AbstractTimeIndexedProblem::xdiff_max_
Eigen::VectorXd xdiff_max_
Maximum change in the variables in a single timestep tau_. Gets set/updated via SetJointVelocityLimit...
Definition: abstract_time_indexed_problem.h:275
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
exotica::AbstractTimeIndexedProblem::tau_
double tau_
Time step duration.
Definition: abstract_time_indexed_problem.h:258
REGISTER_PROBLEM_TYPE
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
Definition: planning_problem.h:45
exotica::TaskSpaceVector
Definition: task_space_vector.h:50
exotica::AbstractTimeIndexedProblem::hessian
std::vector< Hessian > hessian
Definition: abstract_time_indexed_problem.h:233
Eigen::MatrixXdRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
exotica::AbstractTimeIndexedProblem::num_tasks
int num_tasks
Definition: abstract_time_indexed_problem.h:238
exotica::Object::debug_
bool debug_
Definition: object.h:86
exotica::TaskSpaceVector::map
std::vector< TaskVectorEntry > map
Definition: task_space_vector.h:59
exotica::AbstractTimeIndexedProblem::length_jacobian
int length_jacobian
Definition: abstract_time_indexed_problem.h:237
exotica::TimeIndexedTask::Initialize
virtual void Initialize(const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi)
Definition: tasks.cpp:240
exotica::AbstractTimeIndexedProblem::cost
TimeIndexedTask cost
Cost task.
Definition: abstract_time_indexed_problem.h:224
exotica::AbstractTimeIndexedProblem::Phi
std::vector< TaskSpaceVector > Phi
Definition: abstract_time_indexed_problem.h:231
exotica::UnconstrainedTimeIndexedProblem::Instantiate
void Instantiate(const UnconstrainedTimeIndexedProblemInitializer &init) override
Instantiates the problem from an Initializer.
Definition: unconstrained_time_indexed_problem.cpp:37
setup.h
exotica::UnconstrainedTimeIndexedProblem
Unconstrained time-indexed problem.
Definition: unconstrained_time_indexed_problem.h:42
exotica::AbstractTimeIndexedProblem::xdiff
std::vector< Eigen::VectorXd > xdiff
Definition: abstract_time_indexed_problem.h:261
exotica::PlanningProblem::ApplyStartState
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
Definition: planning_problem.cpp:70
exotica::TimeIndexedTask::UpdateS
void UpdateS()
Definition: tasks.cpp:246
exotica::AbstractTimeIndexedProblem::q_dot_max_
Eigen::VectorXd q_dot_max_
Joint velocity limit (rad/s)
Definition: abstract_time_indexed_problem.h:274
exotica::AbstractTimeIndexedProblem::kinematic_solutions_
std::vector< std::shared_ptr< KinematicResponse > > kinematic_solutions_
Definition: abstract_time_indexed_problem.h:270
exotica::PlanningProblem::PreUpdate
virtual void PreUpdate()
Definition: planning_problem.cpp:86
exotica::AbstractTimeIndexedProblem::length_Phi
int length_Phi
Definition: abstract_time_indexed_problem.h:236
exotica::AbstractTimeIndexedProblem::W
Eigen::MatrixXd W
Definition: abstract_time_indexed_problem.h:228
exotica::AbstractTimeIndexedProblem::ct
double ct
Normalisation of scalar cost and Jacobian over trajectory length.
Definition: abstract_time_indexed_problem.h:272
t
geometry_msgs::TransformStamped t
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