Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
exotica::InteractionMesh Class Reference

#include <interaction_mesh.h>

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

Public Member Functions

void AssignScene (ScenePtr scene) override
 
void ComputeGoalLaplace (const Eigen::VectorXd &x, Eigen::VectorXd &goal)
 
Eigen::MatrixXd GetWeights ()
 
void Instantiate (const InteractionMeshInitializer &init) override
 
 InteractionMesh ()
 
void SetWeight (int i, int j, double weight)
 
void SetWeights (const Eigen::MatrixXd &weights)
 
int TaskSpaceDim () override
 
void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
 
void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) override
 
virtual ~InteractionMesh ()
 
- Public Member Functions inherited from exotica::TaskMap
std::vector< KinematicFrameRequestGetFrames () const
 
virtual std::vector< TaskVectorEntryGetLieGroupIndices ()
 
virtual void InstantiateBase (const Initializer &init)
 
virtual void PreUpdate ()
 
virtual int TaskSpaceJacobianDim ()
 
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)
 
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)
 
virtual void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian)
 
- 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
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::InstantiableBase
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
- Public Member Functions inherited from exotica::Instantiable< InteractionMeshInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const InteractionMeshInitializer & GetParameters () const
 
void InstantiateInternal (const Initializer &init) override
 

Static Public Member Functions

static void ComputeGoalLaplace (const std::vector< KDL::Frame > &nodes, Eigen::VectorXd &goal, Eigen::MatrixXdRefConst weights)
 
static Eigen::VectorXd ComputeLaplace (Eigen::VectorXdRefConst eff_Phi, Eigen::MatrixXdRefConst weights, Eigen::MatrixXd *dist=nullptr, Eigen::VectorXd *wsum=nullptr)
 

Protected Member Functions

void Debug (Eigen::VectorXdRefConst phi)
 
void DestroyDebug ()
 
void InitializeDebug (std::string ref)
 

Protected Attributes

int eff_size_ = 0
 
visualization_msgs::Marker imesh_mark_
 
ros::Publisher imesh_mark_pub_
 
Eigen::MatrixXd weights_
 
- Protected Attributes inherited from exotica::TaskMap
std::vector< KinematicFrameRequestframes_
 
ScenePtr scene_
 
- Protected Attributes inherited from exotica::Instantiable< InteractionMeshInitializer >
InteractionMeshInitializer parameters_
 

Additional Inherited Members

- Public Attributes inherited from exotica::TaskMap
int id
 
bool is_used
 
std::vector< KinematicSolutionkinematics
 
int length
 
int length_jacobian
 
int start
 
int start_jacobian
 
- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 

Detailed Description

Definition at line 42 of file interaction_mesh.h.

Constructor & Destructor Documentation

exotica::InteractionMesh::InteractionMesh ( )
default
exotica::InteractionMesh::~InteractionMesh ( )
virtualdefault

Member Function Documentation

void exotica::InteractionMesh::AssignScene ( ScenePtr  scene)
overridevirtual

Reimplemented from exotica::TaskMap.

Definition at line 155 of file interaction_mesh.cpp.

void exotica::InteractionMesh::ComputeGoalLaplace ( const Eigen::VectorXd &  x,
Eigen::VectorXd &  goal 
)

Definition at line 306 of file interaction_mesh.cpp.

void exotica::InteractionMesh::ComputeGoalLaplace ( const std::vector< KDL::Frame > &  nodes,
Eigen::VectorXd &  goal,
Eigen::MatrixXdRefConst  weights 
)
static

Definition at line 293 of file interaction_mesh.cpp.

Eigen::VectorXd exotica::InteractionMesh::ComputeLaplace ( Eigen::VectorXdRefConst  eff_Phi,
Eigen::MatrixXdRefConst  weights,
Eigen::MatrixXd *  dist = nullptr,
Eigen::VectorXd *  wsum = nullptr 
)
static

Compute distance matrix (inverse proportional)

Computer weight normaliser

Compute Laplace coordinates

Definition at line 245 of file interaction_mesh.cpp.

void exotica::InteractionMesh::Debug ( Eigen::VectorXdRefConst  phi)
protected

Definition at line 160 of file interaction_mesh.cpp.

void exotica::InteractionMesh::DestroyDebug ( )
protected

Definition at line 232 of file interaction_mesh.cpp.

Eigen::MatrixXd exotica::InteractionMesh::GetWeights ( )

Definition at line 126 of file interaction_mesh.cpp.

void exotica::InteractionMesh::InitializeDebug ( std::string  ref)
protected

Definition at line 131 of file interaction_mesh.cpp.

void exotica::InteractionMesh::Instantiate ( const InteractionMeshInitializer &  init)
overridevirtual

Reimplemented from exotica::Instantiable< InteractionMeshInitializer >.

Definition at line 139 of file interaction_mesh.cpp.

void exotica::InteractionMesh::SetWeight ( int  i,
int  j,
double  weight 
)

Definition at line 319 of file interaction_mesh.cpp.

void exotica::InteractionMesh::SetWeights ( const Eigen::MatrixXd &  weights)

Definition at line 333 of file interaction_mesh.cpp.

int exotica::InteractionMesh::TaskSpaceDim ( )
overridevirtual

Implements exotica::TaskMap.

Definition at line 240 of file interaction_mesh.cpp.

void exotica::InteractionMesh::Update ( Eigen::VectorXdRefConst  x,
Eigen::VectorXdRef  phi 
)
overridevirtual

Implements exotica::TaskMap.

Definition at line 40 of file interaction_mesh.cpp.

void exotica::InteractionMesh::Update ( Eigen::VectorXdRefConst  x,
Eigen::VectorXdRef  phi,
Eigen::MatrixXdRef  jacobian 
)
overridevirtual

Reimplemented from exotica::TaskMap.

Definition at line 58 of file interaction_mesh.cpp.

Member Data Documentation

int exotica::InteractionMesh::eff_size_ = 0
protected

Definition at line 69 of file interaction_mesh.h.

visualization_msgs::Marker exotica::InteractionMesh::imesh_mark_
protected

Definition at line 72 of file interaction_mesh.h.

ros::Publisher exotica::InteractionMesh::imesh_mark_pub_
protected

Definition at line 71 of file interaction_mesh.h.

Eigen::MatrixXd exotica::InteractionMesh::weights_
protected

Definition at line 68 of file interaction_mesh.h.


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


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09