Public Member Functions | Public Attributes | Protected Attributes | List of all members
exotica::TaskMap Class Referenceabstract

#include <task_map.h>

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

Public Member Functions

virtual void AssignScene (ScenePtr scene)
 
std::vector< KinematicFrameRequestGetFrames () const
 
virtual std::vector< TaskVectorEntryGetLieGroupIndices ()
 
virtual void InstantiateBase (const Initializer &init)
 
virtual void PreUpdate ()
 
virtual int TaskSpaceDim ()=0
 
virtual int TaskSpaceJacobianDim ()
 
virtual void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi)=0
 
virtual void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian)
 
virtual void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian)
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi)
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du)
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du, HessianRef ddphi_ddx, HessianRef ddphi_ddu, HessianRef ddphi_dxdu)
 
- Public Member Functions inherited from exotica::Object
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
 Object ()
 
virtual std::string Print (const std::string &prepend) const
 
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< InitializerGetAllTemplates () const =0
 
virtual Initializer GetInitializerTemplate ()=0
 
 InstantiableBase ()=default
 
virtual void InstantiateInternal (const Initializer &init)=0
 
virtual ~InstantiableBase ()=default
 

Public Attributes

int id = -1
 
bool is_used = false
 
std::vector< KinematicSolutionkinematics = std::vector<KinematicSolution>(1)
 
int length = -1
 
int length_jacobian = -1
 
int start = -1
 
int start_jacobian = -1
 
- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 

Protected Attributes

std::vector< KinematicFrameRequestframes_
 
ScenePtr scene_ = nullptr
 

Additional Inherited Members

- Private Member Functions inherited from exotica::Uncopyable
 Uncopyable ()=default
 
 ~Uncopyable ()=default
 

Detailed Description

Definition at line 52 of file task_map.h.

Member Function Documentation

◆ AssignScene()

void exotica::TaskMap::AssignScene ( ScenePtr  scene)
virtual

Definition at line 37 of file task_map.cpp.

◆ GetFrames()

std::vector< KinematicFrameRequest > exotica::TaskMap::GetFrames ( ) const

Definition at line 57 of file task_map.cpp.

◆ GetLieGroupIndices()

virtual std::vector<TaskVectorEntry> exotica::TaskMap::GetLieGroupIndices ( )
inlinevirtual

Definition at line 75 of file task_map.h.

◆ InstantiateBase()

void exotica::TaskMap::InstantiateBase ( const Initializer init)
virtual

Reimplemented from exotica::InstantiableBase.

Definition at line 42 of file task_map.cpp.

◆ PreUpdate()

virtual void exotica::TaskMap::PreUpdate ( )
inlinevirtual

Definition at line 74 of file task_map.h.

◆ TaskSpaceDim()

virtual int exotica::TaskMap::TaskSpaceDim ( )
pure virtual

◆ TaskSpaceJacobianDim()

virtual int exotica::TaskMap::TaskSpaceJacobianDim ( )
inlinevirtual

Definition at line 73 of file task_map.h.

◆ Update() [1/6]

virtual void exotica::TaskMap::Update ( Eigen::VectorXdRefConst  q,
Eigen::VectorXdRef  phi 
)
pure virtual

◆ Update() [2/6]

void exotica::TaskMap::Update ( Eigen::VectorXdRefConst  q,
Eigen::VectorXdRef  phi,
Eigen::MatrixXdRef  jacobian 
)
virtual

Definition at line 62 of file task_map.cpp.

◆ Update() [3/6]

void exotica::TaskMap::Update ( Eigen::VectorXdRefConst  q,
Eigen::VectorXdRef  phi,
Eigen::MatrixXdRef  jacobian,
HessianRef  hessian 
)
virtual

Definition at line 101 of file task_map.cpp.

◆ Update() [4/6]

void exotica::TaskMap::Update ( Eigen::VectorXdRefConst  x,
Eigen::VectorXdRefConst  u,
Eigen::VectorXdRef  phi 
)
virtual

Definition at line 112 of file task_map.cpp.

◆ Update() [5/6]

void exotica::TaskMap::Update ( Eigen::VectorXdRefConst  x,
Eigen::VectorXdRefConst  u,
Eigen::VectorXdRef  phi,
Eigen::MatrixXdRef  dphi_dx,
Eigen::MatrixXdRef  dphi_du 
)
virtual

Definition at line 118 of file task_map.cpp.

◆ Update() [6/6]

void exotica::TaskMap::Update ( Eigen::VectorXdRefConst  x,
Eigen::VectorXdRefConst  u,
Eigen::VectorXdRef  phi,
Eigen::MatrixXdRef  dphi_dx,
Eigen::MatrixXdRef  dphi_du,
HessianRef  ddphi_ddx,
HessianRef  ddphi_ddu,
HessianRef  ddphi_dxdu 
)
virtual

Definition at line 125 of file task_map.cpp.

Member Data Documentation

◆ frames_

std::vector<KinematicFrameRequest> exotica::TaskMap::frames_
protected

Definition at line 87 of file task_map.h.

◆ id

int exotica::TaskMap::id = -1

Definition at line 79 of file task_map.h.

◆ is_used

bool exotica::TaskMap::is_used = false

Definition at line 84 of file task_map.h.

◆ kinematics

std::vector<KinematicSolution> exotica::TaskMap::kinematics = std::vector<KinematicSolution>(1)

Definition at line 78 of file task_map.h.

◆ length

int exotica::TaskMap::length = -1

Definition at line 81 of file task_map.h.

◆ length_jacobian

int exotica::TaskMap::length_jacobian = -1

Definition at line 83 of file task_map.h.

◆ scene_

ScenePtr exotica::TaskMap::scene_ = nullptr
protected

Definition at line 88 of file task_map.h.

◆ start

int exotica::TaskMap::start = -1

Definition at line 80 of file task_map.h.

◆ start_jacobian

int exotica::TaskMap::start_jacobian = -1

Definition at line 82 of file task_map.h.


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


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:03