abstract_time_indexed_problem.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019, 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 
30 #ifndef EXOTICA_CORE_ABSTRACT_TIME_INDEXED_PROBLEM_H_
31 #define EXOTICA_CORE_ABSTRACT_TIME_INDEXED_PROBLEM_H_
32 
33 #include <Eigen/Sparse>
34 
36 #include <exotica_core/tasks.h>
37 
38 namespace exotica
39 {
41 {
42 public:
45 
48  void Update(Eigen::VectorXdRefConst x_trajectory_in);
49 
53  virtual void Update(Eigen::VectorXdRefConst x_in, int t);
54 
56  double GetDuration() const;
57 
59  std::vector<Eigen::VectorXd> GetInitialTrajectory() const;
60 
63  void SetInitialTrajectory(const std::vector<Eigen::VectorXd>& q_init_in);
64 
66  virtual void PreUpdate();
67 
72  void SetGoal(const std::string& task_name, Eigen::VectorXdRefConst goal, int t = 0);
73 
77  Eigen::VectorXd GetGoal(const std::string& task_name, int t = 0);
78 
83  void SetRho(const std::string& task_name, const double rho, int t = 0);
84 
88  double GetRho(const std::string& task_name, int t = 0);
89 
94  void SetGoalEQ(const std::string& task_name, Eigen::VectorXdRefConst goal, int t = 0);
95 
99  Eigen::VectorXd GetGoalEQ(const std::string& task_name, int t = 0);
100 
105  void SetRhoEQ(const std::string& task_name, const double rho, int t = 0);
106 
110  double GetRhoEQ(const std::string& task_name, int t = 0);
111 
116  void SetGoalNEQ(const std::string& task_name, Eigen::VectorXdRefConst goal, int t = 0);
117 
121  Eigen::VectorXd GetGoalNEQ(const std::string& task_name, int t = 0);
122 
127  void SetRhoNEQ(const std::string& task_name, const double rho, int t = 0);
128 
132  double GetRhoNEQ(const std::string& task_name, int t = 0);
133 
135  Eigen::MatrixXd GetBounds() const;
136 
138  int GetT() const;
139 
141  void SetT(const int T_in);
142 
144  double GetTau() const;
145 
147  void SetTau(const double tau_in);
148 
150  double get_ct() const;
151 
153  double GetScalarTaskCost(int t) const;
154 
156  Eigen::RowVectorXd GetScalarTaskJacobian(int t) const;
157 
159  double GetScalarTransitionCost(int t) const;
160 
162  Eigen::RowVectorXd GetScalarTransitionJacobian(int t) const;
163 
165  double GetCost() const;
166 
168  Eigen::RowVectorXd GetCostJacobian() const;
169 
171  Eigen::VectorXd GetEquality() const;
172 
174  Eigen::VectorXd GetInequality() const;
175 
177  Eigen::SparseMatrix<double> GetEqualityJacobian() const;
178 
180  Eigen::SparseMatrix<double> GetInequalityJacobian() const;
181 
183  std::vector<Eigen::Triplet<double>> GetEqualityJacobianTriplets() const;
184 
187 
189  Eigen::VectorXd GetEquality(int t) const;
190 
192  Eigen::MatrixXd GetEqualityJacobian(int t) const;
193 
195  Eigen::VectorXd GetInequality(int t) const;
196 
198  Eigen::MatrixXd GetInequalityJacobian(int t) const;
199 
201  std::vector<Eigen::Triplet<double>> GetInequalityJacobianTriplets() const;
202 
205 
208 
210  Eigen::VectorXd GetJointVelocityConstraint() const;
211 
213  Eigen::MatrixXd GetJointVelocityConstraintBounds() const;
214 
216  std::vector<Eigen::Triplet<double>> GetJointVelocityConstraintJacobianTriplets() const;
217 
219  Eigen::VectorXd GetJointVelocityLimits() const;
220 
222  void SetJointVelocityLimits(const Eigen::VectorXd& qdot_max_in);
223 
227 
228  Eigen::MatrixXd W; // TODO(wxm): Make private and add getter and setter (#209)
229 
230  // TODO: Make private and add getter (no need to be public!)
231  std::vector<TaskSpaceVector> Phi;
232  std::vector<Eigen::MatrixXd> jacobian;
233  std::vector<Hessian> hessian;
234 
235  // TODO: Make private and add getter/setter
240 
241 protected:
242  virtual void ReinitializeVariables();
243 
245  inline void ValidateTimeIndex(int& t_in) const
246  {
247  if (t_in >= T_ || t_in < -1)
248  {
249  ThrowPretty("Requested t=" << t_in << " out of range, needs to be 0 =< t < " << T_);
250  }
251  else if (t_in == -1)
252  {
253  t_in = (T_ - 1);
254  }
255  }
256 
257  int T_ = 0;
258  double tau_ = 0;
259 
260  std::vector<Eigen::VectorXd> x;
261  std::vector<Eigen::VectorXd> xdiff; // equivalent to dx = x(t)-x(t-1)
262 
263  double w_scale_ = 1.0;
264 
268 
269  std::vector<Eigen::VectorXd> initial_trajectory_;
270  std::vector<std::shared_ptr<KinematicResponse>> kinematic_solutions_;
271 
272  double ct;
273 
274  Eigen::VectorXd q_dot_max_;
275  Eigen::VectorXd xdiff_max_;
276 
277  // The first element in the pair is the timestep (t) and the second element is the task.id (id).
278  std::vector<std::pair<int, int>> active_nonlinear_equality_constraints_;
279  std::vector<std::pair<int, int>> active_nonlinear_inequality_constraints_;
282 
283  // Terms related with the joint velocity constraint - the Jacobian triplets are constant so can be cached.
285  std::vector<Eigen::Triplet<double>> joint_velocity_constraint_jacobian_triplets_;
286 };
287 } // namespace exotica
288 
289 #endif // EXOTICA_CORE_ABSTRACT_TIME_INDEXED_PROBLEM_H_
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
Sets goal for a given task at a given timestep (equality task).
std::vector< Eigen::Triplet< double > > GetEqualityJacobianTriplets() const
Returns a vector of triplets to fill a sparse Jacobian for the equality constraints.
double GetDuration() const
Returns the duration of the trajectory (T * tau).
void Update(Eigen::VectorXdRefConst x_trajectory_in)
Updates the entire problem from a given trajectory (e.g., used in an optimization solver) ...
std::vector< std::pair< int, int > > active_nonlinear_equality_constraints_
Eigen::MatrixXd GetJointVelocityConstraintBounds() const
Returns the joint velocity constraint bounds (constant terms).
double GetScalarTaskCost(int t) const
Returns the scalar task cost at timestep t.
void SetT(const int T_in)
Sets the number of timesteps in the trajectory. Note: Rho/Goal need to be updated for every timestep ...
Eigen::VectorXd GetInequality() const
Returns the inequality constraint values for the entire trajectory.
TimeIndexedTask equality
General equality task.
Eigen::RowVectorXd GetScalarTaskJacobian(int t) const
Returns the Jacobian of the scalar task cost at timestep t.
void SetRhoNEQ(const std::string &task_name, const double rho, int t=0)
Sets Rho for a given task at a given timestep (inequality task).
double get_ct() const
Returns the cost scaling factor.
Eigen::VectorXd GetJointVelocityConstraint() const
Returns the joint velocity constraint inequality terms (linear).
#define ThrowPretty(m)
Definition: exception.h:36
double GetRho(const std::string &task_name, int t=0)
Returns the precision (Rho) for a given task at a given timestep (cost task).
std::vector< Eigen::Triplet< double > > GetJointVelocityConstraintJacobianTriplets() const
Returns the joint velocity constraint Jacobian as triplets.
Eigen::VectorXd GetGoalEQ(const std::string &task_name, int t=0)
Returns the goal for a given task at a given timestep (equality task).
std::vector< std::pair< int, int > > active_nonlinear_inequality_constraints_
std::vector< Eigen::Triplet< double > > joint_velocity_constraint_jacobian_triplets_
int get_active_nonlinear_inequality_constraints_dimension() const
Returns the dimension of the active inequality constraints.
Eigen::VectorXd GetGoalNEQ(const std::string &task_name, int t=0)
Returns the goal for a given task at a given timestep (goal task).
int GetT() const
Returns the number of timesteps in the trajectory.
double GetTau() const
Returns the time discretization tau for the trajectory.
double GetCost() const
Returns the scalar cost for the entire trajectory (both task and transition cost).
TimeIndexedTask inequality
General inequality task.
Eigen::VectorXd GetJointVelocityLimits() const
Returns the per-DoF joint velocity limit vector.
double GetRhoEQ(const std::string &task_name, int t=0)
Returns the precision (Rho) for a given task at a given timestep (equality task). ...
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
Sets goal for a given task at a given timestep (inequality task).
std::vector< Eigen::VectorXd > x
Current internal problem state.
Eigen::RowVectorXd GetScalarTransitionJacobian(int t) const
Returns the Jacobian of the transition cost at timestep t.
std::vector< Eigen::Triplet< double > > GetInequalityJacobianTriplets() const
Returns a vector of triplets to fill a sparse Jacobian for the inequality constraints.
void SetRhoEQ(const std::string &task_name, const double rho, int t=0)
Sets Rho for a given task at a given timestep (equality task).
double w_scale_
Kinematic system transition error covariance multiplier (constant throughout the trajectory) ...
int get_joint_velocity_constraint_dimension() const
Returns the dimension of the joint velocity constraint (linear inequality).
double GetScalarTransitionCost(int t) const
Returns the scalar transition cost (x^T*W*x) at timestep t.
Eigen::RowVectorXd GetCostJacobian() const
Returns the Jacobian of the scalar cost over the entire trajectory (Jacobian of GetCost).
Eigen::VectorXd GetGoal(const std::string &task_name, int t=0)
Returns the goal for a given task at a given timestep (cost task).
Eigen::MatrixXd GetBounds() const
Returns the joint bounds (first column lower, second column upper).
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
void SetJointVelocityLimits(const Eigen::VectorXd &qdot_max_in)
Sets the joint velocity limits. Supports N- and 1-dimensional vectors.
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
Sets goal for a given task at a given timestep (cost task).
double GetRhoNEQ(const std::string &task_name, int t=0)
Returns the precision (Rho) for a given task at a given timestep (equality task). ...
std::vector< Eigen::VectorXd > GetInitialTrajectory() const
Returns the initial trajectory/seed.
void SetInitialTrajectory(const std::vector< Eigen::VectorXd > &q_init_in)
Sets the initial trajectory/seed.
void ValidateTimeIndex(int &t_in) const
Checks the desired time index for bounds and supports -1 indexing.
virtual void PreUpdate()
Updates internal variables before solving, e.g., after setting new values for Rho.
std::vector< std::shared_ptr< KinematicResponse > > kinematic_solutions_
Eigen::SparseMatrix< double > GetEqualityJacobian() const
Returns the sparse Jacobian matrix of the equality constraints over the entire trajectory.
Eigen::VectorXd xdiff_max_
Maximum change in the variables in a single timestep tau_. Gets set/updated via SetJointVelocityLimit...
int get_active_nonlinear_equality_constraints_dimension() const
Returns the dimension of the active equality constraints.
void SetRho(const std::string &task_name, const double rho, int t=0)
Sets Rho for a given task at a given timestep (cost task).
Eigen::VectorXd GetEquality() const
Returns the equality constraint values for the entire trajectory.
double ct
Normalisation of scalar cost and Jacobian over trajectory length.
Eigen::VectorXd q_dot_max_
Joint velocity limit (rad/s)
void SetTau(const double tau_in)
Sets the time discretization tau for the trajectory.
std::vector< Eigen::VectorXd > initial_trajectory_
Eigen::SparseMatrix< double > GetInequalityJacobian() const
Returns the sparse Jacobian matrix of the inequality constraints over the entire trajectory.


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:34:49