#include <dynamic_time_indexed_shooting_problem.h>
Public Member Functions | |
Eigen::VectorXd | ApplyStartState (bool update_traj=true) override |
void | DisableStochasticUpdates () |
DynamicTimeIndexedShootingProblem () | |
void | EnableStochasticUpdates () |
double | get_control_cost_weight () const |
Eigen::MatrixXd | get_F (int t) const |
Returns the noise weight matrix at time t. More... | |
const ControlCostLossTermType & | get_loss_type () const |
const Eigen::MatrixXd & | get_Q (int t) const |
Returns the precision matrix at time step t. More... | |
const Eigen::MatrixXd & | get_Qf () const |
Returns the cost weight matrix at time N. More... | |
const Eigen::MatrixXd & | get_R () const |
Returns the control weight matrix. More... | |
const int & | get_T () const |
Returns the number of timesteps in the state trajectory. More... | |
const double & | get_tau () const |
Returns the discretization timestep tau. More... | |
const Eigen::MatrixXd & | get_U () const |
Returns the control trajectory U. More... | |
Eigen::VectorXd | get_U (int t) const |
Returns the control state at time t. More... | |
const Eigen::MatrixXd & | get_X () const |
Returns the state trajectory X. More... | |
Eigen::VectorXd | get_X (int t) const |
Returns the state at time t. More... | |
const Eigen::MatrixXd & | get_X_star () const |
Returns the target state trajectory X. More... | |
double | GetControlCost (int t) const |
Eigen::MatrixXd | GetControlCostHessian (int t) |
luu More... | |
Eigen::VectorXd | GetControlCostJacobian (int t) |
lu More... | |
const Eigen::MatrixXd & | GetControlNoiseJacobian (int column_idx) const |
F[i]_u. More... | |
Eigen::MatrixXd | GetStateControlCostHessian () |
double | GetStateCost (int t) const |
Eigen::MatrixXd | GetStateCostHessian (int t) |
lxx More... | |
Eigen::VectorXd | GetStateCostJacobian (int t) |
lx More... | |
void | Instantiate (const DynamicTimeIndexedShootingProblemInitializer &init) override |
void | OnSolverIterationEnd () |
lxu == lux More... | |
void | PreUpdate () override |
void | set_control_cost_weight (const double control_cost_weight_in) |
void | set_loss_type (const ControlCostLossTermType &loss_type_in) |
void | set_Q (Eigen::MatrixXdRefConst Q_in, int t) |
Sets the precision matrix for time step t. More... | |
void | set_Qf (Eigen::MatrixXdRefConst Q_in) |
Sets the cost weight matrix for time N. More... | |
void | set_T (const int &T_in) |
Sets the number of timesteps in the state trajectory. More... | |
void | set_U (Eigen::MatrixXdRefConst U_in) |
Sets the control trajectory U (can be used as the initial guess) More... | |
void | set_X (Eigen::MatrixXdRefConst X_in) |
Sets the state trajectory X (can be used as the initial guess) More... | |
void | set_X_star (Eigen::MatrixXdRefConst X_star_in) |
Sets the target state trajectory X. More... | |
void | Update (Eigen::VectorXdRefConst u, int t) |
void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, int t) |
void | UpdateTerminalState (Eigen::VectorXdRefConst x) |
virtual | ~DynamicTimeIndexedShootingProblem () |
Public Member Functions inherited from exotica::PlanningProblem | |
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 | |
InstantiableBase ()=default | |
virtual | ~InstantiableBase ()=default |
Public Member Functions inherited from exotica::Instantiable< DynamicTimeIndexedShootingProblemInitializer > | |
std::vector< Initializer > | GetAllTemplates () const override |
Initializer | GetInitializerTemplate () override |
const DynamicTimeIndexedShootingProblemInitializer & | GetParameters () const |
void | InstantiateInternal (const Initializer &init) override |
Public Attributes | |
TimeIndexedTask | cost |
Cost task. More... | |
std::vector< Hessian > | ddPhi_ddu |
Stacked TaskMap Hessian w.r.t. control. More... | |
std::vector< Hessian > | ddPhi_ddx |
Stacked TaskMap Hessian w.r.t. state. More... | |
std::vector< Hessian > | ddPhi_dxdu |
Stacked TaskMap Hessian w.r.t. state and control. More... | |
std::vector< Eigen::MatrixXd > | dPhi_du |
Stacked TaskMap Jacobian w.r.t. control. More... | |
std::vector< Eigen::MatrixXd > | dPhi_dx |
Stacked TaskMap Jacobian w.r.t. state. More... | |
int | length_jacobian |
Length of tangent vector to Phi. More... | |
int | length_Phi |
Length of TaskSpaceVector (Phi => stacked task-maps) More... | |
int | num_tasks |
Number of TaskMaps. More... | |
std::vector< TaskSpaceVector > | Phi |
Stacked TaskMap vector. More... | |
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 | |
void | InstantiateCostTerms (const DynamicTimeIndexedShootingProblemInitializer &init) |
void | ReinitializeVariables () |
void | UpdateTaskMaps (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, int t) |
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 | |
Eigen::VectorXd | bimodal_huber_mode1_ |
Eigen::VectorXd | bimodal_huber_mode2_ |
std::vector< Eigen::MatrixXd > | Ci_ |
Noise weight terms. More... | |
std::vector< Eigen::MatrixXd > | control_cost_hessian_ |
std::vector< Eigen::VectorXd > | control_cost_jacobian_ |
double | control_cost_weight_ = 1 |
TaskSpaceVector | cost_Phi |
Eigen::MatrixXd | CW_ |
White noise covariance. More... | |
std::vector< Eigen::MatrixXd > | dxdiff_ |
std::vector< Eigen::MatrixXd > | general_cost_hessian_ |
std::vector< Eigen::VectorXd > | general_cost_jacobian_ |
std::mt19937 | generator_ |
Eigen::VectorXd | huber_rate_ |
std::vector< std::shared_ptr< KinematicResponse > > | kinematic_solutions_ |
Eigen::VectorXd | l1_rate_ |
ControlCostLossTermType | loss_type_ |
std::vector< Eigen::MatrixXd > | Q_ |
State space penalty matrix (precision matrix), per time index. More... | |
Eigen::MatrixXd | Qf_ |
Final state cost. More... | |
Eigen::MatrixXd | R_ |
Control space penalty matrix. More... | |
Eigen::VectorXd | smooth_l1_mean_ |
Eigen::VectorXd | smooth_l1_std_ |
std::normal_distribution< double > | standard_normal_noise_ {0, 1} |
std::vector< Eigen::MatrixXd > | state_cost_hessian_ |
std::vector< Eigen::VectorXd > | state_cost_jacobian_ |
bool | stochastic_matrices_specified_ = false |
bool | stochastic_updates_enabled_ = false |
int | T_ |
Number of time steps. More... | |
double | tau_ |
Time step duration. More... | |
Eigen::MatrixXd | U_ |
Control trajectory. Size: num-controls x (T-1) More... | |
Eigen::MatrixXd | X_ |
State trajectory (i.e., positions, velocities). Size: num-states x T. More... | |
Eigen::MatrixXd | X_diff_ |
Difference between X_ and X_star_. Size: ndx x T. More... | |
Eigen::MatrixXd | X_star_ |
Goal state trajectory (i.e., positions, velocities). Size: num-states x T. 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_ |
Protected Attributes inherited from exotica::Instantiable< DynamicTimeIndexedShootingProblemInitializer > | |
DynamicTimeIndexedShootingProblemInitializer | parameters_ |
Definition at line 50 of file dynamic_time_indexed_shooting_problem.h.
exotica::DynamicTimeIndexedShootingProblem::DynamicTimeIndexedShootingProblem | ( | ) |
Definition at line 40 of file dynamic_time_indexed_shooting_problem.cpp.
|
virtualdefault |
|
overridevirtual |
Reimplemented from exotica::PlanningProblem.
Definition at line 430 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::DisableStochasticUpdates | ( | ) |
Definition at line 932 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::EnableStochasticUpdates | ( | ) |
Definition at line 927 of file dynamic_time_indexed_shooting_problem.cpp.
|
inline |
Definition at line 167 of file dynamic_time_indexed_shooting_problem.h.
Eigen::MatrixXd exotica::DynamicTimeIndexedShootingProblem::get_F | ( | int | t | ) | const |
Returns the noise weight matrix at time t.
Definition at line 903 of file dynamic_time_indexed_shooting_problem.cpp.
|
inline |
Definition at line 165 of file dynamic_time_indexed_shooting_problem.h.
const Eigen::MatrixXd & exotica::DynamicTimeIndexedShootingProblem::get_Q | ( | int | t | ) | const |
Returns the precision matrix at time step t.
Definition at line 499 of file dynamic_time_indexed_shooting_problem.cpp.
const Eigen::MatrixXd & exotica::DynamicTimeIndexedShootingProblem::get_Qf | ( | ) | const |
Returns the cost weight matrix at time N.
Definition at line 505 of file dynamic_time_indexed_shooting_problem.cpp.
const Eigen::MatrixXd & exotica::DynamicTimeIndexedShootingProblem::get_R | ( | ) | const |
Returns the control weight matrix.
Definition at line 510 of file dynamic_time_indexed_shooting_problem.cpp.
const int & exotica::DynamicTimeIndexedShootingProblem::get_T | ( | ) | const |
Returns the number of timesteps in the state trajectory.
Definition at line 387 of file dynamic_time_indexed_shooting_problem.cpp.
const double & exotica::DynamicTimeIndexedShootingProblem::get_tau | ( | ) | const |
Returns the discretization timestep tau.
Definition at line 402 of file dynamic_time_indexed_shooting_problem.cpp.
const Eigen::MatrixXd & exotica::DynamicTimeIndexedShootingProblem::get_U | ( | ) | const |
Returns the control trajectory U.
Definition at line 462 of file dynamic_time_indexed_shooting_problem.cpp.
Eigen::VectorXd exotica::DynamicTimeIndexedShootingProblem::get_U | ( | int | t | ) | const |
Returns the control state at time t.
Definition at line 467 of file dynamic_time_indexed_shooting_problem.cpp.
const Eigen::MatrixXd & exotica::DynamicTimeIndexedShootingProblem::get_X | ( | ) | const |
Returns the state trajectory X.
Definition at line 436 of file dynamic_time_indexed_shooting_problem.cpp.
Eigen::VectorXd exotica::DynamicTimeIndexedShootingProblem::get_X | ( | int | t | ) | const |
Returns the state at time t.
Definition at line 441 of file dynamic_time_indexed_shooting_problem.cpp.
const Eigen::MatrixXd & exotica::DynamicTimeIndexedShootingProblem::get_X_star | ( | ) | const |
Returns the target state trajectory X.
Definition at line 479 of file dynamic_time_indexed_shooting_problem.cpp.
double exotica::DynamicTimeIndexedShootingProblem::GetControlCost | ( | int | t | ) | const |
Definition at line 826 of file dynamic_time_indexed_shooting_problem.cpp.
Eigen::MatrixXd exotica::DynamicTimeIndexedShootingProblem::GetControlCostHessian | ( | int | t | ) |
luu
Definition at line 793 of file dynamic_time_indexed_shooting_problem.cpp.
Eigen::VectorXd exotica::DynamicTimeIndexedShootingProblem::GetControlCostJacobian | ( | int | t | ) |
lu
Definition at line 867 of file dynamic_time_indexed_shooting_problem.cpp.
const Eigen::MatrixXd & exotica::DynamicTimeIndexedShootingProblem::GetControlNoiseJacobian | ( | int | column_idx | ) | const |
F[i]_u.
Definition at line 920 of file dynamic_time_indexed_shooting_problem.cpp.
|
inline |
Definition at line 115 of file dynamic_time_indexed_shooting_problem.h.
double exotica::DynamicTimeIndexedShootingProblem::GetStateCost | ( | int | t | ) | const |
Definition at line 735 of file dynamic_time_indexed_shooting_problem.cpp.
Eigen::MatrixXd exotica::DynamicTimeIndexedShootingProblem::GetStateCostHessian | ( | int | t | ) |
lxx
Definition at line 758 of file dynamic_time_indexed_shooting_problem.cpp.
Eigen::VectorXd exotica::DynamicTimeIndexedShootingProblem::GetStateCostJacobian | ( | int | t | ) |
lx
Definition at line 743 of file dynamic_time_indexed_shooting_problem.cpp.
|
overridevirtual |
Reimplemented from exotica::Instantiable< DynamicTimeIndexedShootingProblemInitializer >.
Definition at line 110 of file dynamic_time_indexed_shooting_problem.cpp.
|
protected |
Definition at line 46 of file dynamic_time_indexed_shooting_problem.cpp.
|
inline |
lxu == lux
Definition at line 124 of file dynamic_time_indexed_shooting_problem.h.
|
overridevirtual |
Reimplemented from exotica::PlanningProblem.
Definition at line 407 of file dynamic_time_indexed_shooting_problem.cpp.
|
protected |
Definition at line 249 of file dynamic_time_indexed_shooting_problem.cpp.
|
inline |
Definition at line 168 of file dynamic_time_indexed_shooting_problem.h.
|
inline |
Definition at line 166 of file dynamic_time_indexed_shooting_problem.h.
void exotica::DynamicTimeIndexedShootingProblem::set_Q | ( | Eigen::MatrixXdRefConst | Q_in, |
int | t | ||
) |
Sets the precision matrix for time step t.
Definition at line 515 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::set_Qf | ( | Eigen::MatrixXdRefConst | Q_in | ) |
Sets the cost weight matrix for time N.
Definition at line 522 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::set_T | ( | const int & | T_in | ) |
Sets the number of timesteps in the state trajectory.
Definition at line 392 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::set_U | ( | Eigen::MatrixXdRefConst | U_in | ) |
Sets the control trajectory U (can be used as the initial guess)
Definition at line 473 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::set_X | ( | Eigen::MatrixXdRefConst | X_in | ) |
Sets the state trajectory X (can be used as the initial guess)
Definition at line 447 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::set_X_star | ( | Eigen::MatrixXdRefConst | X_star_in | ) |
Sets the target state trajectory X.
Definition at line 484 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::Update | ( | Eigen::VectorXdRefConst | u, |
int | t | ||
) |
Definition at line 613 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::Update | ( | Eigen::VectorXdRefConst | x, |
Eigen::VectorXdRefConst | u, | ||
int | t | ||
) |
Definition at line 527 of file dynamic_time_indexed_shooting_problem.cpp.
|
protected |
Definition at line 661 of file dynamic_time_indexed_shooting_problem.cpp.
void exotica::DynamicTimeIndexedShootingProblem::UpdateTerminalState | ( | Eigen::VectorXdRefConst | x | ) |
Definition at line 628 of file dynamic_time_indexed_shooting_problem.cpp.
|
inlineprotected |
Checks the desired time index for bounds and supports -1 indexing.
Definition at line 172 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 227 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 227 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Noise weight terms.
Definition at line 201 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 211 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 210 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 220 of file dynamic_time_indexed_shooting_problem.h.
TimeIndexedTask exotica::DynamicTimeIndexedShootingProblem::cost |
Cost task.
Definition at line 95 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 218 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
White noise covariance.
Definition at line 202 of file dynamic_time_indexed_shooting_problem.h.
std::vector<Hessian> exotica::DynamicTimeIndexedShootingProblem::ddPhi_ddu |
Stacked TaskMap Hessian w.r.t. control.
Definition at line 100 of file dynamic_time_indexed_shooting_problem.h.
std::vector<Hessian> exotica::DynamicTimeIndexedShootingProblem::ddPhi_ddx |
Stacked TaskMap Hessian w.r.t. state.
Definition at line 99 of file dynamic_time_indexed_shooting_problem.h.
std::vector<Hessian> exotica::DynamicTimeIndexedShootingProblem::ddPhi_dxdu |
Stacked TaskMap Hessian w.r.t. state and control.
Definition at line 101 of file dynamic_time_indexed_shooting_problem.h.
std::vector<Eigen::MatrixXd> exotica::DynamicTimeIndexedShootingProblem::dPhi_du |
Stacked TaskMap Jacobian w.r.t. control.
Definition at line 98 of file dynamic_time_indexed_shooting_problem.h.
std::vector<Eigen::MatrixXd> exotica::DynamicTimeIndexedShootingProblem::dPhi_dx |
Stacked TaskMap Jacobian w.r.t. state.
Definition at line 97 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 205 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 209 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 208 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 215 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 226 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 213 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 225 of file dynamic_time_indexed_shooting_problem.h.
int exotica::DynamicTimeIndexedShootingProblem::length_jacobian |
Length of tangent vector to Phi.
Definition at line 105 of file dynamic_time_indexed_shooting_problem.h.
int exotica::DynamicTimeIndexedShootingProblem::length_Phi |
Length of TaskSpaceVector (Phi => stacked task-maps)
Definition at line 104 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 221 of file dynamic_time_indexed_shooting_problem.h.
int exotica::DynamicTimeIndexedShootingProblem::num_tasks |
Number of TaskMaps.
Definition at line 106 of file dynamic_time_indexed_shooting_problem.h.
std::vector<TaskSpaceVector> exotica::DynamicTimeIndexedShootingProblem::Phi |
Stacked TaskMap vector.
Definition at line 96 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
State space penalty matrix (precision matrix), per time index.
Definition at line 198 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Final state cost.
Definition at line 197 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Control space penalty matrix.
Definition at line 199 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 229 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 229 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 216 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 207 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 206 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 189 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Definition at line 190 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Number of time steps.
Definition at line 187 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Time step duration.
Definition at line 188 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Control trajectory. Size: num-controls x (T-1)
Definition at line 193 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
State trajectory (i.e., positions, velocities). Size: num-states x T.
Definition at line 192 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Difference between X_ and X_star_. Size: ndx x T.
Definition at line 195 of file dynamic_time_indexed_shooting_problem.h.
|
protected |
Goal state trajectory (i.e., positions, velocities). Size: num-states x T.
Definition at line 194 of file dynamic_time_indexed_shooting_problem.h.