#include <tasks.h>
Public Member Functions | |
Eigen::VectorXd | GetGoal (const std::string &task_name, int t) const |
double | GetRho (const std::string &task_name, int t) const |
Eigen::MatrixXd | GetS (const std::string &task_name, int t) const |
Eigen::VectorXd | GetTaskError (const std::string &task_name, int t) const |
virtual void | Initialize (const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi) |
void | ReinitializeVariables (int _T, std::shared_ptr< PlanningProblem > _prob, const TaskSpaceVector &_Phi) |
void | SetGoal (const std::string &task_name, Eigen::VectorXdRefConst goal, int t) |
void | SetRho (const std::string &task_name, const double rho_in, int t) |
TimeIndexedTask ()=default | |
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) |
void | Update (const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_dPhi_dx, Eigen::MatrixXdRefConst big_dPhi_du, int t) |
void | Update (const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_jacobian, HessianRefConst big_hessian, int t) |
void | Update (const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_jacobian, int t) |
void | Update (const TaskSpaceVector &big_Phi, int t) |
void | UpdateS () |
void | ValidateTimeIndex (int &t_in) const |
virtual | ~TimeIndexedTask ()=default |
Public Member Functions inherited from exotica::Task | |
Task ()=default | |
virtual | ~Task ()=default |
Public Attributes | |
std::vector< Hessian > | ddPhi_ddu |
std::vector< Hessian > | ddPhi_ddx |
std::vector< Hessian > | ddPhi_dxdu |
std::vector< Eigen::MatrixXd > | dPhi_du |
std::vector< Eigen::MatrixXd > | dPhi_dx |
std::vector< Hessian > | hessian |
std::vector< Eigen::MatrixXd > | jacobian |
std::vector< TaskSpaceVector > | Phi |
std::vector< Eigen::VectorXd > | rho |
std::vector< Eigen::MatrixXd > | S |
int | T |
std::vector< TaskSpaceVector > | y |
std::vector< Eigen::VectorXd > | ydiff |
Public Attributes inherited from exotica::Task | |
std::vector< TaskIndexing > | indexing |
int | length_jacobian |
int | length_Phi |
int | num_tasks |
TaskMapMap | task_maps |
TaskMapVec | tasks |
double | tolerance = 0.0 |
Additional Inherited Members | |
Protected Attributes inherited from exotica::Task | |
std::vector< TaskInitializer > | task_initializers_ |
|
default |
|
virtualdefault |
Eigen::VectorXd exotica::TimeIndexedTask::GetGoal | ( | const std::string & | task_name, |
int | t | ||
) | const |
double exotica::TimeIndexedTask::GetRho | ( | const std::string & | task_name, |
int | t | ||
) | const |
Eigen::MatrixXd exotica::TimeIndexedTask::GetS | ( | const std::string & | task_name, |
int | t | ||
) | const |
Eigen::VectorXd exotica::TimeIndexedTask::GetTaskError | ( | const std::string & | task_name, |
int | t | ||
) | const |
|
virtual |
Reimplemented from exotica::Task.
void exotica::TimeIndexedTask::ReinitializeVariables | ( | int | _T, |
std::shared_ptr< PlanningProblem > | _prob, | ||
const TaskSpaceVector & | _Phi | ||
) |
void exotica::TimeIndexedTask::SetGoal | ( | const std::string & | task_name, |
Eigen::VectorXdRefConst | goal, | ||
int | t | ||
) |
void exotica::TimeIndexedTask::SetRho | ( | const std::string & | task_name, |
const double | rho_in, | ||
int | t | ||
) |
void exotica::TimeIndexedTask::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 | ||
) |
void exotica::TimeIndexedTask::Update | ( | const TaskSpaceVector & | big_Phi, |
Eigen::MatrixXdRefConst | big_dPhi_dx, | ||
Eigen::MatrixXdRefConst | big_dPhi_du, | ||
int | t | ||
) |
void exotica::TimeIndexedTask::Update | ( | const TaskSpaceVector & | big_Phi, |
Eigen::MatrixXdRefConst | big_jacobian, | ||
HessianRefConst | big_hessian, | ||
int | t | ||
) |
void exotica::TimeIndexedTask::Update | ( | const TaskSpaceVector & | big_Phi, |
Eigen::MatrixXdRefConst | big_jacobian, | ||
int | t | ||
) |
void exotica::TimeIndexedTask::Update | ( | const TaskSpaceVector & | big_Phi, |
int | t | ||
) |
|
inline |
std::vector<Eigen::MatrixXd> exotica::TimeIndexedTask::dPhi_du |
std::vector<Eigen::MatrixXd> exotica::TimeIndexedTask::dPhi_dx |
std::vector<Eigen::MatrixXd> exotica::TimeIndexedTask::jacobian |
std::vector<TaskSpaceVector> exotica::TimeIndexedTask::Phi |
std::vector<Eigen::VectorXd> exotica::TimeIndexedTask::rho |
std::vector<TaskSpaceVector> exotica::TimeIndexedTask::y |
std::vector<Eigen::VectorXd> exotica::TimeIndexedTask::ydiff |