#include <abstract_time_indexed_problem.h>
Public Member Functions | |
AbstractTimeIndexedProblem () | |
int | get_active_nonlinear_equality_constraints_dimension () const |
Returns the dimension of the active equality constraints. More... | |
int | get_active_nonlinear_inequality_constraints_dimension () const |
Returns the dimension of the active inequality constraints. More... | |
double | get_ct () const |
Returns the cost scaling factor. More... | |
int | get_joint_velocity_constraint_dimension () const |
Returns the dimension of the joint velocity constraint (linear inequality). More... | |
Eigen::MatrixXd | GetBounds () const |
Returns the joint bounds (first column lower, second column upper). More... | |
double | GetCost () const |
Returns the scalar cost for the entire trajectory (both task and transition cost). More... | |
Eigen::RowVectorXd | GetCostJacobian () const |
Returns the Jacobian of the scalar cost over the entire trajectory (Jacobian of GetCost). More... | |
double | GetDuration () const |
Returns the duration of the trajectory (T * tau). More... | |
Eigen::VectorXd | GetEquality () const |
Returns the equality constraint values for the entire trajectory. More... | |
Eigen::VectorXd | GetEquality (int t) const |
Returns the value of the equality constraints at timestep t. More... | |
Eigen::SparseMatrix< double > | GetEqualityJacobian () const |
Returns the sparse Jacobian matrix of the equality constraints over the entire trajectory. More... | |
Eigen::MatrixXd | GetEqualityJacobian (int t) const |
Returns the Jacobian of the equality constraints at timestep t. More... | |
std::vector< Eigen::Triplet< double > > | GetEqualityJacobianTriplets () const |
Returns a vector of triplets to fill a sparse Jacobian for the equality constraints. More... | |
Eigen::VectorXd | GetGoal (const std::string &task_name, int t=0) |
Returns the goal for a given task at a given timestep (cost task). More... | |
Eigen::VectorXd | GetGoalEQ (const std::string &task_name, int t=0) |
Returns the goal for a given task at a given timestep (equality task). More... | |
Eigen::VectorXd | GetGoalNEQ (const std::string &task_name, int t=0) |
Returns the goal for a given task at a given timestep (goal task). More... | |
Eigen::VectorXd | GetInequality () const |
Returns the inequality constraint values for the entire trajectory. More... | |
Eigen::VectorXd | GetInequality (int t) const |
Returns the value of the inequality constraints at timestep t. More... | |
Eigen::SparseMatrix< double > | GetInequalityJacobian () const |
Returns the sparse Jacobian matrix of the inequality constraints over the entire trajectory. More... | |
Eigen::MatrixXd | GetInequalityJacobian (int t) const |
Returns the Jacobian of the inequality constraints at timestep t. More... | |
std::vector< Eigen::Triplet< double > > | GetInequalityJacobianTriplets () const |
Returns a vector of triplets to fill a sparse Jacobian for the inequality constraints. More... | |
std::vector< Eigen::VectorXd > | GetInitialTrajectory () const |
Returns the initial trajectory/seed. More... | |
Eigen::VectorXd | GetJointVelocityConstraint () const |
Returns the joint velocity constraint inequality terms (linear). More... | |
Eigen::MatrixXd | GetJointVelocityConstraintBounds () const |
Returns the joint velocity constraint bounds (constant terms). More... | |
std::vector< Eigen::Triplet< double > > | GetJointVelocityConstraintJacobianTriplets () const |
Returns the joint velocity constraint Jacobian as triplets. More... | |
Eigen::VectorXd | GetJointVelocityLimits () const |
Returns the per-DoF joint velocity limit vector. More... | |
double | GetRho (const std::string &task_name, int t=0) |
Returns the precision (Rho) for a given task at a given timestep (cost task). More... | |
double | GetRhoEQ (const std::string &task_name, int t=0) |
Returns the precision (Rho) for a given task at a given timestep (equality task). More... | |
double | GetRhoNEQ (const std::string &task_name, int t=0) |
Returns the precision (Rho) for a given task at a given timestep (equality task). More... | |
double | GetScalarTaskCost (int t) const |
Returns the scalar task cost at timestep t. More... | |
Eigen::RowVectorXd | GetScalarTaskJacobian (int t) const |
Returns the Jacobian of the scalar task cost at timestep t. More... | |
double | GetScalarTransitionCost (int t) const |
Returns the scalar transition cost (x^T*W*x) at timestep t. More... | |
Eigen::RowVectorXd | GetScalarTransitionJacobian (int t) const |
Returns the Jacobian of the transition cost at timestep t. More... | |
int | GetT () const |
Returns the number of timesteps in the trajectory. More... | |
double | GetTau () const |
Returns the time discretization tau for the trajectory. More... | |
virtual void | PreUpdate () |
Updates internal variables before solving, e.g., after setting new values for Rho. More... | |
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). More... | |
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). More... | |
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). More... | |
void | SetInitialTrajectory (const std::vector< Eigen::VectorXd > &q_init_in) |
Sets the initial trajectory/seed. More... | |
void | SetJointVelocityLimits (const Eigen::VectorXd &qdot_max_in) |
Sets the joint velocity limits. Supports N- and 1-dimensional vectors. More... | |
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). More... | |
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). More... | |
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). More... | |
void | SetT (const int T_in) |
Sets the number of timesteps in the trajectory. Note: Rho/Goal need to be updated for every timestep after calling this method. More... | |
void | SetTau (const double tau_in) |
Sets the time discretization tau for the trajectory. More... | |
void | Update (Eigen::VectorXdRefConst x_trajectory_in) |
Updates the entire problem from a given trajectory (e.g., used in an optimization solver) More... | |
virtual void | Update (Eigen::VectorXdRefConst x_in, int t) |
Updates an individual timestep from a given state vector. More... | |
virtual | ~AbstractTimeIndexedProblem () |
Public Member Functions inherited from exotica::PlanningProblem | |
virtual Eigen::VectorXd | ApplyStartState (bool update_traj=true) |
int | get_num_controls () const |
int | get_num_positions () const |
! Dimension of planning problem. TODO: Update from positions/velocities/controls and make private. More... | |
int | get_num_velocities () const |
std::pair< std::vector< double >, std::vector< double > > | GetCostEvolution () const |
double | GetCostEvolution (int index) const |
KinematicRequestFlags | GetFlags () const |
int | GetNumberOfIterations () const |
unsigned int | GetNumberOfProblemUpdates () const |
ScenePtr | GetScene () const |
Eigen::VectorXd | GetStartState () const |
double | GetStartTime () const |
TaskMapMap & | GetTaskMaps () |
TaskMapVec & | GetTasks () |
void | InstantiateBase (const Initializer &init) override |
virtual bool | IsValid () |
Evaluates whether the problem is valid. More... | |
PlanningProblem () | |
std::string | Print (const std::string &prepend) const override |
void | ResetCostEvolution (size_t size) |
void | ResetNumberOfProblemUpdates () |
void | SetCostEvolution (int index, double value) |
void | SetStartState (Eigen::VectorXdRefConst x) |
void | SetStartTime (double t) |
virtual | ~PlanningProblem () |
Public Member Functions inherited from exotica::Object | |
std::string | GetObjectName () |
void | InstantiateObject (const Initializer &init) |
Object () | |
virtual std::string | type () const |
Type Information wrapper: must be virtual so that it is polymorphic... More... | |
virtual | ~Object () |
Public Member Functions inherited from exotica::InstantiableBase | |
virtual std::vector< Initializer > | GetAllTemplates () const =0 |
virtual Initializer | GetInitializerTemplate ()=0 |
InstantiableBase ()=default | |
virtual void | InstantiateInternal (const Initializer &init)=0 |
virtual | ~InstantiableBase ()=default |
Public Attributes | |
TimeIndexedTask | cost |
Cost task. More... | |
TimeIndexedTask | equality |
General equality task. More... | |
std::vector< Hessian > | hessian |
TimeIndexedTask | inequality |
General inequality task. More... | |
std::vector< Eigen::MatrixXd > | jacobian |
int | length_jacobian |
int | length_Phi |
int | num_tasks |
std::vector< TaskSpaceVector > | Phi |
bool | use_bounds |
Eigen::MatrixXd | W |
Public Attributes inherited from exotica::PlanningProblem | |
int | N = 0 |
double | t_start |
TerminationCriterion | termination_criterion |
Public Attributes inherited from exotica::Object | |
bool | debug_ |
std::string | ns_ |
std::string | object_name_ |
Protected Member Functions | |
virtual void | ReinitializeVariables () |
void | ValidateTimeIndex (int &t_in) const |
Checks the desired time index for bounds and supports -1 indexing. More... | |
Protected Member Functions inherited from exotica::PlanningProblem | |
void | UpdateMultipleTaskKinematics (std::vector< std::shared_ptr< KinematicResponse >> responses) |
void | UpdateTaskKinematics (std::shared_ptr< KinematicResponse > response) |
Protected Attributes | |
std::vector< std::pair< int, int > > | active_nonlinear_equality_constraints_ |
int | active_nonlinear_equality_constraints_dimension_ = 0 |
std::vector< std::pair< int, int > > | active_nonlinear_inequality_constraints_ |
int | active_nonlinear_inequality_constraints_dimension_ = 0 |
TaskSpaceVector | cost_Phi |
double | ct |
Normalisation of scalar cost and Jacobian over trajectory length. More... | |
TaskSpaceVector | equality_Phi |
TaskSpaceVector | inequality_Phi |
std::vector< Eigen::VectorXd > | initial_trajectory_ |
int | joint_velocity_constraint_dimension_ = 0 |
std::vector< Eigen::Triplet< double > > | joint_velocity_constraint_jacobian_triplets_ |
std::vector< std::shared_ptr< KinematicResponse > > | kinematic_solutions_ |
Eigen::VectorXd | q_dot_max_ |
Joint velocity limit (rad/s) More... | |
int | T_ = 0 |
Number of time steps. More... | |
double | tau_ = 0 |
Time step duration. More... | |
double | w_scale_ = 1.0 |
Kinematic system transition error covariance multiplier (constant throughout the trajectory) More... | |
std::vector< Eigen::VectorXd > | x |
Current internal problem state. More... | |
std::vector< Eigen::VectorXd > | xdiff |
Eigen::VectorXd | xdiff_max_ |
Maximum change in the variables in a single timestep tau_. Gets set/updated via SetJointVelocityLimits or ReinitializeVariables. More... | |
Protected Attributes inherited from exotica::PlanningProblem | |
std::vector< std::pair< std::chrono::high_resolution_clock::time_point, double > > | cost_evolution_ |
KinematicRequestFlags | flags_ = KinematicRequestFlags::KIN_FK |
unsigned int | number_of_problem_updates_ = 0 |
ScenePtr | scene_ |
Eigen::VectorXd | start_state_ |
TaskMapMap | task_maps_ |
TaskMapVec | tasks_ |
Definition at line 40 of file abstract_time_indexed_problem.h.
exotica::AbstractTimeIndexedProblem::AbstractTimeIndexedProblem | ( | ) |
Definition at line 35 of file abstract_time_indexed_problem.cpp.
|
virtualdefault |
int exotica::AbstractTimeIndexedProblem::get_active_nonlinear_equality_constraints_dimension | ( | ) | const |
Returns the dimension of the active equality constraints.
Definition at line 339 of file abstract_time_indexed_problem.cpp.
int exotica::AbstractTimeIndexedProblem::get_active_nonlinear_inequality_constraints_dimension | ( | ) | const |
Returns the dimension of the active inequality constraints.
Definition at line 344 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::get_ct | ( | ) | const |
Returns the cost scaling factor.
Definition at line 289 of file abstract_time_indexed_problem.cpp.
int exotica::AbstractTimeIndexedProblem::get_joint_velocity_constraint_dimension | ( | ) | const |
Returns the dimension of the joint velocity constraint (linear inequality).
Definition at line 487 of file abstract_time_indexed_problem.cpp.
Eigen::MatrixXd exotica::AbstractTimeIndexedProblem::GetBounds | ( | ) | const |
Returns the joint bounds (first column lower, second column upper).
Definition at line 42 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::GetCost | ( | ) | const |
Returns the scalar cost for the entire trajectory (both task and transition cost).
Definition at line 294 of file abstract_time_indexed_problem.cpp.
Eigen::RowVectorXd exotica::AbstractTimeIndexedProblem::GetCostJacobian | ( | ) | const |
Returns the Jacobian of the scalar cost over the entire trajectory (Jacobian of GetCost).
Definition at line 304 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::GetDuration | ( | ) | const |
Returns the duration of the trajectory (T * tau).
Definition at line 199 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetEquality | ( | ) | const |
Returns the equality constraint values for the entire trajectory.
Definition at line 349 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetEquality | ( | int | t | ) | const |
Returns the value of the equality constraints at timestep t.
Definition at line 406 of file abstract_time_indexed_problem.cpp.
Eigen::SparseMatrix< double > exotica::AbstractTimeIndexedProblem::GetEqualityJacobian | ( | ) | const |
Returns the sparse Jacobian matrix of the equality constraints over the entire trajectory.
Definition at line 364 of file abstract_time_indexed_problem.cpp.
Eigen::MatrixXd exotica::AbstractTimeIndexedProblem::GetEqualityJacobian | ( | int | t | ) | const |
Returns the Jacobian of the equality constraints at timestep t.
Definition at line 412 of file abstract_time_indexed_problem.cpp.
std::vector< Eigen::Triplet< double > > exotica::AbstractTimeIndexedProblem::GetEqualityJacobianTriplets | ( | ) | const |
Returns a vector of triplets to fill a sparse Jacobian for the equality constraints.
Definition at line 372 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetGoal | ( | const std::string & | task_name, |
int | t = 0 |
||
) |
Returns the goal for a given task at a given timestep (cost task).
task_name | Name of task |
t | Timestep |
Definition at line 564 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetGoalEQ | ( | const std::string & | task_name, |
int | t = 0 |
||
) |
Returns the goal for a given task at a given timestep (equality task).
task_name | Name of task |
t | Timestep |
Definition at line 585 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetGoalNEQ | ( | const std::string & | task_name, |
int | t = 0 |
||
) |
Returns the goal for a given task at a given timestep (goal task).
task_name | Name of task |
t | Timestep |
Definition at line 606 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetInequality | ( | ) | const |
Returns the inequality constraint values for the entire trajectory.
Definition at line 418 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetInequality | ( | int | t | ) | const |
Returns the value of the inequality constraints at timestep t.
Definition at line 475 of file abstract_time_indexed_problem.cpp.
Eigen::SparseMatrix< double > exotica::AbstractTimeIndexedProblem::GetInequalityJacobian | ( | ) | const |
Returns the sparse Jacobian matrix of the inequality constraints over the entire trajectory.
Definition at line 433 of file abstract_time_indexed_problem.cpp.
Eigen::MatrixXd exotica::AbstractTimeIndexedProblem::GetInequalityJacobian | ( | int | t | ) | const |
Returns the Jacobian of the inequality constraints at timestep t.
Definition at line 481 of file abstract_time_indexed_problem.cpp.
std::vector< Eigen::Triplet< double > > exotica::AbstractTimeIndexedProblem::GetInequalityJacobianTriplets | ( | ) | const |
Returns a vector of triplets to fill a sparse Jacobian for the inequality constraints.
Definition at line 441 of file abstract_time_indexed_problem.cpp.
std::vector< Eigen::VectorXd > exotica::AbstractTimeIndexedProblem::GetInitialTrajectory | ( | ) | const |
Returns the initial trajectory/seed.
Definition at line 194 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetJointVelocityConstraint | ( | ) | const |
Returns the joint velocity constraint inequality terms (linear).
Definition at line 514 of file abstract_time_indexed_problem.cpp.
Eigen::MatrixXd exotica::AbstractTimeIndexedProblem::GetJointVelocityConstraintBounds | ( | ) | const |
Returns the joint velocity constraint bounds (constant terms).
Definition at line 524 of file abstract_time_indexed_problem.cpp.
std::vector< Eigen::Triplet< double > > exotica::AbstractTimeIndexedProblem::GetJointVelocityConstraintJacobianTriplets | ( | ) | const |
Returns the joint velocity constraint Jacobian as triplets.
Definition at line 547 of file abstract_time_indexed_problem.cpp.
Eigen::VectorXd exotica::AbstractTimeIndexedProblem::GetJointVelocityLimits | ( | ) | const |
Returns the per-DoF joint velocity limit vector.
Definition at line 492 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::GetRho | ( | const std::string & | task_name, |
int | t = 0 |
||
) |
Returns the precision (Rho) for a given task at a given timestep (cost task).
task_name | Name of task |
t | Timestep |
Definition at line 569 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::GetRhoEQ | ( | const std::string & | task_name, |
int | t = 0 |
||
) |
Returns the precision (Rho) for a given task at a given timestep (equality task).
task_name | Name of task |
t | Timestep |
Definition at line 590 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::GetRhoNEQ | ( | const std::string & | task_name, |
int | t = 0 |
||
) |
Returns the precision (Rho) for a given task at a given timestep (equality task).
task_name | Name of task |
t | Timestep |
Definition at line 611 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::GetScalarTaskCost | ( | int | t | ) | const |
Returns the scalar task cost at timestep t.
Definition at line 315 of file abstract_time_indexed_problem.cpp.
Eigen::RowVectorXd exotica::AbstractTimeIndexedProblem::GetScalarTaskJacobian | ( | int | t | ) | const |
Returns the Jacobian of the scalar task cost at timestep t.
Definition at line 321 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::GetScalarTransitionCost | ( | int | t | ) | const |
Returns the scalar transition cost (x^T*W*x) at timestep t.
Definition at line 327 of file abstract_time_indexed_problem.cpp.
Eigen::RowVectorXd exotica::AbstractTimeIndexedProblem::GetScalarTransitionJacobian | ( | int | t | ) | const |
Returns the Jacobian of the transition cost at timestep t.
Definition at line 333 of file abstract_time_indexed_problem.cpp.
int exotica::AbstractTimeIndexedProblem::GetT | ( | ) | const |
Returns the number of timesteps in the trajectory.
Definition at line 112 of file abstract_time_indexed_problem.cpp.
double exotica::AbstractTimeIndexedProblem::GetTau | ( | ) | const |
Returns the time discretization tau for the trajectory.
Definition at line 127 of file abstract_time_indexed_problem.cpp.
|
virtual |
Updates internal variables before solving, e.g., after setting new values for Rho.
Reimplemented from exotica::PlanningProblem.
Reimplemented in exotica::UnconstrainedTimeIndexedProblem, and exotica::BoundedTimeIndexedProblem.
Definition at line 139 of file abstract_time_indexed_problem.cpp.
|
protectedvirtual |
Reimplemented in exotica::UnconstrainedTimeIndexedProblem, and exotica::BoundedTimeIndexedProblem.
Definition at line 47 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetGoal | ( | const std::string & | task_name, |
Eigen::VectorXdRefConst | goal, | ||
int | t = 0 |
||
) |
Sets goal for a given task at a given timestep (cost task).
task_name | Name of task |
goal | Goal |
t | Timestep |
Definition at line 553 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetGoalEQ | ( | const std::string & | task_name, |
Eigen::VectorXdRefConst | goal, | ||
int | t = 0 |
||
) |
Sets goal for a given task at a given timestep (equality task).
task_name | Name of task |
goal | Goal |
t | Timestep |
Definition at line 574 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetGoalNEQ | ( | const std::string & | task_name, |
Eigen::VectorXdRefConst | goal, | ||
int | t = 0 |
||
) |
Sets goal for a given task at a given timestep (inequality task).
task_name | Name of task |
goal | Goal |
t | Timestep |
Definition at line 595 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetInitialTrajectory | ( | const std::vector< Eigen::VectorXd > & | q_init_in | ) |
Sets the initial trajectory/seed.
q_init_in | Vector of states. Expects T states of dimension N. |
Definition at line 181 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetJointVelocityLimits | ( | const Eigen::VectorXd & | qdot_max_in | ) |
Sets the joint velocity limits. Supports N- and 1-dimensional vectors.
Definition at line 497 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetRho | ( | const std::string & | task_name, |
const double | rho, | ||
int | t = 0 |
||
) |
Sets Rho for a given task at a given timestep (cost task).
task_name | Name of task |
rho | Rho (scaling/precision) |
t | Timestep |
Definition at line 558 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetRhoEQ | ( | const std::string & | task_name, |
const double | rho, | ||
int | t = 0 |
||
) |
Sets Rho for a given task at a given timestep (equality task).
task_name | Name of task |
rho | Rho (scaling/precision) |
t | Timestep |
Definition at line 579 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetRhoNEQ | ( | const std::string & | task_name, |
const double | rho, | ||
int | t = 0 |
||
) |
Sets Rho for a given task at a given timestep (inequality task).
task_name | Name of task |
rho | Rho (scaling/precision) |
t | Timestep |
Definition at line 600 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetT | ( | const int | T_in | ) |
Sets the number of timesteps in the trajectory. Note: Rho/Goal need to be updated for every timestep after calling this method.
Definition at line 117 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::SetTau | ( | const double | tau_in | ) |
Sets the time discretization tau for the trajectory.
Definition at line 132 of file abstract_time_indexed_problem.cpp.
void exotica::AbstractTimeIndexedProblem::Update | ( | Eigen::VectorXdRefConst | x_trajectory_in | ) |
Updates the entire problem from a given trajectory (e.g., used in an optimization solver)
x_trajectory_in | Trajectory flattened as a vector; expects dimension: (T - 1) * N |
Definition at line 204 of file abstract_time_indexed_problem.cpp.
|
virtual |
Updates an individual timestep from a given state vector.
x_in | State |
t | Timestep to update |
Reimplemented in exotica::UnconstrainedTimeIndexedProblem, and exotica::BoundedTimeIndexedProblem.
Definition at line 215 of file abstract_time_indexed_problem.cpp.
|
inlineprotected |
Checks the desired time index for bounds and supports -1 indexing.
Definition at line 245 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 278 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 280 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 279 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 281 of file abstract_time_indexed_problem.h.
TimeIndexedTask exotica::AbstractTimeIndexedProblem::cost |
Cost task.
Definition at line 224 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 265 of file abstract_time_indexed_problem.h.
|
protected |
Normalisation of scalar cost and Jacobian over trajectory length.
Definition at line 272 of file abstract_time_indexed_problem.h.
TimeIndexedTask exotica::AbstractTimeIndexedProblem::equality |
General equality task.
Definition at line 226 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 267 of file abstract_time_indexed_problem.h.
std::vector<Hessian> exotica::AbstractTimeIndexedProblem::hessian |
Definition at line 233 of file abstract_time_indexed_problem.h.
TimeIndexedTask exotica::AbstractTimeIndexedProblem::inequality |
General inequality task.
Definition at line 225 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 266 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 269 of file abstract_time_indexed_problem.h.
std::vector<Eigen::MatrixXd> exotica::AbstractTimeIndexedProblem::jacobian |
Definition at line 232 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 284 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 285 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 270 of file abstract_time_indexed_problem.h.
int exotica::AbstractTimeIndexedProblem::length_jacobian |
Definition at line 237 of file abstract_time_indexed_problem.h.
int exotica::AbstractTimeIndexedProblem::length_Phi |
Definition at line 236 of file abstract_time_indexed_problem.h.
int exotica::AbstractTimeIndexedProblem::num_tasks |
Definition at line 238 of file abstract_time_indexed_problem.h.
std::vector<TaskSpaceVector> exotica::AbstractTimeIndexedProblem::Phi |
Definition at line 231 of file abstract_time_indexed_problem.h.
|
protected |
Joint velocity limit (rad/s)
Definition at line 274 of file abstract_time_indexed_problem.h.
|
protected |
Number of time steps.
Definition at line 257 of file abstract_time_indexed_problem.h.
|
protected |
Time step duration.
Definition at line 258 of file abstract_time_indexed_problem.h.
bool exotica::AbstractTimeIndexedProblem::use_bounds |
Definition at line 239 of file abstract_time_indexed_problem.h.
Eigen::MatrixXd exotica::AbstractTimeIndexedProblem::W |
Definition at line 228 of file abstract_time_indexed_problem.h.
|
protected |
Kinematic system transition error covariance multiplier (constant throughout the trajectory)
Definition at line 263 of file abstract_time_indexed_problem.h.
|
protected |
Current internal problem state.
Definition at line 260 of file abstract_time_indexed_problem.h.
|
protected |
Definition at line 261 of file abstract_time_indexed_problem.h.
|
protected |
Maximum change in the variables in a single timestep tau_. Gets set/updated via SetJointVelocityLimits or ReinitializeVariables.
Definition at line 275 of file abstract_time_indexed_problem.h.