Public Member Functions | Private Member Functions | Private Attributes | List of all members
exotica::PointToPlane Class Reference

PointToPlane TaskMap: Penalises the z-distance between two frames - or the distance of a point (represented by the Link frame) spanned by the normal represented through the z-axis of a second frame (represented by the Base frame). More...

#include <point_to_plane.h>

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

Public Member Functions

void Instantiate (const PointToPlaneInitializer &init) override
 
int TaskSpaceDim () override
 
void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) override
 
void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) override
 
void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian) override
 
- Public Member Functions inherited from exotica::TaskMap
virtual void AssignScene (ScenePtr scene)
 
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)
 
- 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< PointToPlaneInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const PointToPlaneInitializer & GetParameters () const
 
void InstantiateInternal (const Initializer &init) override
 

Private Member Functions

void PublishDebug ()
 

Private Attributes

ros::Publisher debug_pub_
 

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_
 
- Protected Attributes inherited from exotica::TaskMap
std::vector< KinematicFrameRequestframes_
 
ScenePtr scene_
 
- Protected Attributes inherited from exotica::Instantiable< PointToPlaneInitializer >
PointToPlaneInitializer parameters_
 

Detailed Description

PointToPlane TaskMap: Penalises the z-distance between two frames - or the distance of a point (represented by the Link frame) spanned by the normal represented through the z-axis of a second frame (represented by the Base frame).

This TaskMap returns the signed distance to the plane by default. In an unconstrained optimisation this would correspond to an equality constraint and force the distance to the plane to be minimised. In order to use the TaskMap as an inequality constraint, the parameter 'PositiveOnly' can be set to true. In this case, the TaskMap applies a ReLU-like activation ($x = (0, x)$) to the output.

Definition at line 47 of file point_to_plane.h.

Member Function Documentation

◆ Instantiate()

void exotica::PointToPlane::Instantiate ( const PointToPlaneInitializer &  init)
overridevirtual

Reimplemented from exotica::Instantiable< PointToPlaneInitializer >.

Definition at line 39 of file point_to_plane.cpp.

◆ PublishDebug()

void exotica::PointToPlane::PublishDebug ( )
private

Definition at line 143 of file point_to_plane.cpp.

◆ TaskSpaceDim()

int exotica::PointToPlane::TaskSpaceDim ( )
overridevirtual

Implements exotica::TaskMap.

Definition at line 138 of file point_to_plane.cpp.

◆ Update() [1/3]

void exotica::PointToPlane::Update ( Eigen::VectorXdRefConst  q,
Eigen::VectorXdRef  phi 
)
overridevirtual

Implements exotica::TaskMap.

Definition at line 57 of file point_to_plane.cpp.

◆ Update() [2/3]

void exotica::PointToPlane::Update ( Eigen::VectorXdRefConst  q,
Eigen::VectorXdRef  phi,
Eigen::MatrixXdRef  jacobian 
)
overridevirtual

Reimplemented from exotica::TaskMap.

Definition at line 76 of file point_to_plane.cpp.

◆ Update() [3/3]

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

Reimplemented from exotica::TaskMap.

Definition at line 113 of file point_to_plane.cpp.

Member Data Documentation

◆ debug_pub_

ros::Publisher exotica::PointToPlane::debug_pub_
private

Definition at line 59 of file point_to_plane.h.


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


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Mon Feb 28 2022 22:25:17