Public Member Functions | Public Attributes | List of all members
exotica::TimeIndexedTask Struct Reference

#include <tasks.h>

Inheritance diagram for exotica::TimeIndexedTask:
Inheritance graph
[legend]

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< HessianddPhi_ddu
 
std::vector< HessianddPhi_ddx
 
std::vector< HessianddPhi_dxdu
 
std::vector< Eigen::MatrixXd > dPhi_du
 
std::vector< Eigen::MatrixXd > dPhi_dx
 
std::vector< Hessianhessian
 
std::vector< Eigen::MatrixXd > jacobian
 
std::vector< TaskSpaceVectorPhi
 
std::vector< Eigen::VectorXdrho
 
std::vector< Eigen::MatrixXd > S
 
int T
 
std::vector< TaskSpaceVectory
 
std::vector< Eigen::VectorXdydiff
 
- Public Attributes inherited from exotica::Task
std::vector< TaskIndexingindexing
 
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_
 

Detailed Description

Definition at line 75 of file tasks.h.

Constructor & Destructor Documentation

◆ TimeIndexedTask()

exotica::TimeIndexedTask::TimeIndexedTask ( )
default

◆ ~TimeIndexedTask()

virtual exotica::TimeIndexedTask::~TimeIndexedTask ( )
virtualdefault

Member Function Documentation

◆ GetGoal()

Eigen::VectorXd exotica::TimeIndexedTask::GetGoal ( const std::string &  task_name,
int  t 
) const

Definition at line 352 of file tasks.cpp.

◆ GetRho()

double exotica::TimeIndexedTask::GetRho ( const std::string &  task_name,
int  t 
) const

Definition at line 380 of file tasks.cpp.

◆ GetS()

Eigen::MatrixXd exotica::TimeIndexedTask::GetS ( const std::string &  task_name,
int  t 
) const

Definition at line 406 of file tasks.cpp.

◆ GetTaskError()

Eigen::VectorXd exotica::TimeIndexedTask::GetTaskError ( const std::string &  task_name,
int  t 
) const

Definition at line 393 of file tasks.cpp.

◆ Initialize()

void exotica::TimeIndexedTask::Initialize ( const std::vector< exotica::Initializer > &  inits,
std::shared_ptr< PlanningProblem prob,
TaskSpaceVector Phi 
)
virtual

Reimplemented from exotica::Task.

Definition at line 240 of file tasks.cpp.

◆ ReinitializeVariables()

void exotica::TimeIndexedTask::ReinitializeVariables ( int  _T,
std::shared_ptr< PlanningProblem _prob,
const TaskSpaceVector _Phi 
)

Definition at line 420 of file tasks.cpp.

◆ SetGoal()

void exotica::TimeIndexedTask::SetGoal ( const std::string &  task_name,
Eigen::VectorXdRefConst  goal,
int  t 
)

Definition at line 337 of file tasks.cpp.

◆ SetRho()

void exotica::TimeIndexedTask::SetRho ( const std::string &  task_name,
const double  rho_in,
int  t 
)

Definition at line 365 of file tasks.cpp.

◆ Update() [1/5]

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 
)

Definition at line 261 of file tasks.cpp.

◆ Update() [2/5]

void exotica::TimeIndexedTask::Update ( const TaskSpaceVector big_Phi,
Eigen::MatrixXdRefConst  big_dPhi_dx,
Eigen::MatrixXdRefConst  big_dPhi_du,
int  t 
)

Definition at line 281 of file tasks.cpp.

◆ Update() [3/5]

void exotica::TimeIndexedTask::Update ( const TaskSpaceVector big_Phi,
Eigen::MatrixXdRefConst  big_jacobian,
HessianRefConst  big_hessian,
int  t 
)

Definition at line 295 of file tasks.cpp.

◆ Update() [4/5]

void exotica::TimeIndexedTask::Update ( const TaskSpaceVector big_Phi,
Eigen::MatrixXdRefConst  big_jacobian,
int  t 
)

Definition at line 306 of file tasks.cpp.

◆ Update() [5/5]

void exotica::TimeIndexedTask::Update ( const TaskSpaceVector big_Phi,
int  t 
)

Definition at line 316 of file tasks.cpp.

◆ UpdateS()

void exotica::TimeIndexedTask::UpdateS ( )

Definition at line 246 of file tasks.cpp.

◆ ValidateTimeIndex()

void exotica::TimeIndexedTask::ValidateTimeIndex ( int &  t_in) const
inline

Definition at line 325 of file tasks.cpp.

Member Data Documentation

◆ ddPhi_ddu

std::vector<Hessian> exotica::TimeIndexedTask::ddPhi_ddu

Definition at line 118 of file tasks.h.

◆ ddPhi_ddx

std::vector<Hessian> exotica::TimeIndexedTask::ddPhi_ddx

Definition at line 117 of file tasks.h.

◆ ddPhi_dxdu

std::vector<Hessian> exotica::TimeIndexedTask::ddPhi_dxdu

Definition at line 119 of file tasks.h.

◆ dPhi_du

std::vector<Eigen::MatrixXd> exotica::TimeIndexedTask::dPhi_du

Definition at line 122 of file tasks.h.

◆ dPhi_dx

std::vector<Eigen::MatrixXd> exotica::TimeIndexedTask::dPhi_dx

Definition at line 121 of file tasks.h.

◆ hessian

std::vector<Hessian> exotica::TimeIndexedTask::hessian

Definition at line 116 of file tasks.h.

◆ jacobian

std::vector<Eigen::MatrixXd> exotica::TimeIndexedTask::jacobian

Definition at line 120 of file tasks.h.

◆ Phi

std::vector<TaskSpaceVector> exotica::TimeIndexedTask::Phi

Definition at line 115 of file tasks.h.

◆ rho

std::vector<Eigen::VectorXd> exotica::TimeIndexedTask::rho

Definition at line 112 of file tasks.h.

◆ S

std::vector<Eigen::MatrixXd> exotica::TimeIndexedTask::S

Definition at line 123 of file tasks.h.

◆ T

int exotica::TimeIndexedTask::T

Definition at line 124 of file tasks.h.

◆ y

std::vector<TaskSpaceVector> exotica::TimeIndexedTask::y

Definition at line 113 of file tasks.h.

◆ ydiff

std::vector<Eigen::VectorXd> exotica::TimeIndexedTask::ydiff

Definition at line 114 of file tasks.h.


The documentation for this struct was generated from the following files:


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Oct 20 2023 02:59:49