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

#include <point_to_line.h>

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

Public Member Functions

Eigen::Vector3d GetEndPoint ()
 
void Instantiate (const PointToLineInitializer &init) override
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PointToLine ()
 
void SetEndPoint (const Eigen::Vector3d &point)
 
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 ~PointToLine ()
 
- 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)
 
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< PointToLineInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const PointToLineInitializer & GetParameters () const
 
void InstantiateInternal (const Initializer &init) override
 

Private Member Functions

Eigen::Vector3d Direction (const Eigen::Vector3d &point)
 direction computes the vector from a point to its projection on a line More...
 

Private Attributes

std::string base_name_
 frame of defined line More...
 
bool infinite_
 
Eigen::Vector3d line_
 vector from start to end point of line More...
 
Eigen::Vector3d line_end_
 end point of line in base frame More...
 
Eigen::Vector3d line_start_
 start point of line in base frame More...
 
std::string link_name_
 frame of defined point More...
 
ros::Publisher pub_marker_
 publish marker for RViz More...
 
ros::Publisher pub_marker_label_
 marker label More...
 
bool visualize_
 

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< PointToLineInitializer >
PointToLineInitializer parameters_
 

Detailed Description

Definition at line 39 of file point_to_line.h.

Constructor & Destructor Documentation

exotica::PointToLine::PointToLine ( )
default
exotica::PointToLine::~PointToLine ( )
virtualdefault

Member Function Documentation

Eigen::Vector3d exotica::PointToLine::Direction ( const Eigen::Vector3d &  point)
private

direction computes the vector from a point to its projection on a line

Parameters
pointpoint in base frame
Returns
3D vector from #point to its projection on #line

Definition at line 40 of file point_to_line.cpp.

Eigen::Vector3d exotica::PointToLine::GetEndPoint ( )

Definition at line 72 of file point_to_line.cpp.

void exotica::PointToLine::Instantiate ( const PointToLineInitializer &  init)
overridevirtual

Reimplemented from exotica::Instantiable< PointToLineInitializer >.

Definition at line 228 of file point_to_line.cpp.

void exotica::PointToLine::SetEndPoint ( const Eigen::Vector3d &  point)

Definition at line 77 of file point_to_line.cpp.

int exotica::PointToLine::TaskSpaceDim ( )
overridevirtual

Implements exotica::TaskMap.

Definition at line 255 of file point_to_line.cpp.

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

Implements exotica::TaskMap.

Definition at line 83 of file point_to_line.cpp.

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

Reimplemented from exotica::TaskMap.

Definition at line 94 of file point_to_line.cpp.

Member Data Documentation

std::string exotica::PointToLine::base_name_
private

frame of defined line

Definition at line 68 of file point_to_line.h.

bool exotica::PointToLine::infinite_
private

true: vector from start to end defines the direction of and infinite line false: start and end define a line segment

Definition at line 64 of file point_to_line.h.

Eigen::Vector3d exotica::PointToLine::line_
private

vector from start to end point of line

Definition at line 63 of file point_to_line.h.

Eigen::Vector3d exotica::PointToLine::line_end_
private

end point of line in base frame

Definition at line 62 of file point_to_line.h.

Eigen::Vector3d exotica::PointToLine::line_start_
private

start point of line in base frame

Definition at line 61 of file point_to_line.h.

std::string exotica::PointToLine::link_name_
private

frame of defined point

Definition at line 67 of file point_to_line.h.

ros::Publisher exotica::PointToLine::pub_marker_
private

publish marker for RViz

Definition at line 70 of file point_to_line.h.

ros::Publisher exotica::PointToLine::pub_marker_label_
private

marker label

Definition at line 71 of file point_to_line.h.

bool exotica::PointToLine::visualize_
private

Definition at line 73 of file point_to_line.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