Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
jsk_recognition_utils::Line Class Reference

Class to represent 3-D straight line. More...

#include <line.h>

Inheritance diagram for jsk_recognition_utils::Line:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< LinePtr
 

Public Member Functions

virtual double angle (const Line &other) const
 compute angle between a given line. More...
 
virtual double computeAlpha (const Point &p) const
 
virtual double distance (const Line &other) const
 compute a distance to line. More...
 
virtual double distanceToPoint (const Eigen::Vector3f &from) const
 compute a distance to a point More...
 
virtual double distanceToPoint (const Eigen::Vector3f &from, Eigen::Vector3f &foot) const
 compute a distance to a point and foot point will be assigned to foot. More...
 
virtual PointPair findEndPoints (const Vertices &points) const
 Extract end points from the points on the lines. More...
 
virtual Line::Ptr flip ()
 
virtual void foot (const Eigen::Vector3f &point, Eigen::Vector3f &output) const
 compute a point which gives perpendicular projection. More...
 
virtual void getDirection (Eigen::Vector3f &output) const
 get normalized direction vector of the line and assign it to output. More...
 
virtual Eigen::Vector3f getDirection () const
 get normalized direction vector of the line. More...
 
virtual void getOrigin (Eigen::Vector3f &output) const
 get origin of the line and assing it to output. More...
 
virtual Eigen::Vector3f getOrigin () const
 get origin of the line. More...
 
virtual bool isParallel (const Line &other, double angle_threshold=0.1) const
 return true if given line is parallel. angle_threshold is error tolerance. More...
 
virtual bool isPerpendicular (const Line &other, double angle_threshold=0.1) const
 return true if given line is perpendicular. angle_threshold is error tolerance. More...
 
virtual bool isSameDirection (const Line &other) const
 
 Line (const Eigen::Vector3f &direction, const Eigen::Vector3f &origin)
 Construct a line from direction vector and a point on the line. More...
 
virtual Ptr midLine (const Line &other) const
 compute a middle line between given line. More...
 
virtual void parallelLineNormal (const Line &other, Eigen::Vector3f &output) const
 compute a perpendicular line of two lines from origin_ More...
 
virtual Ptr parallelLineOnAPoint (const Eigen::Vector3f &p) const
 compute a line on a point, whose direction is same to the current line. More...
 
virtual void point (double alpha, Eigen::Vector3f &ouptut)
 Compute a point on normal from alpha parameter. More...
 
virtual void print ()
 Print Line information. More...
 

Static Public Member Functions

static Ptr fromCoefficients (const std::vector< float > &coefficients)
 Instantiate Line from array of float. More...
 

Protected Attributes

Eigen::Vector3f direction_
 
Eigen::Vector3f origin_
 

Detailed Description

Class to represent 3-D straight line.

Definition at line 49 of file line.h.

Member Typedef Documentation

Definition at line 52 of file line.h.

Constructor & Destructor Documentation

jsk_recognition_utils::Line::Line ( const Eigen::Vector3f &  direction,
const Eigen::Vector3f &  origin 
)

Construct a line from direction vector and a point on the line.

Parameters
directiondirection of the line. non-normalized vector is allowed.
originpoint on the line.

Definition at line 43 of file line.cpp.

Member Function Documentation

double jsk_recognition_utils::Line::angle ( const Line other) const
virtual

compute angle between a given line.

Definition at line 88 of file line.cpp.

double jsk_recognition_utils::Line::computeAlpha ( const Point p) const
virtual

@ brief Let equation of line's scale factor a.

x = a d + p where d is a normalized direction vector and p is a point on the vector.

Definition at line 168 of file line.cpp.

double jsk_recognition_utils::Line::distance ( const Line other) const
virtual

compute a distance to line.

Definition at line 155 of file line.cpp.

double jsk_recognition_utils::Line::distanceToPoint ( const Eigen::Vector3f &  from) const
virtual

compute a distance to a point

Definition at line 82 of file line.cpp.

double jsk_recognition_utils::Line::distanceToPoint ( const Eigen::Vector3f &  from,
Eigen::Vector3f &  foot 
) const
virtual

compute a distance to a point and foot point will be assigned to foot.

Definition at line 75 of file line.cpp.

PointPair jsk_recognition_utils::Line::findEndPoints ( const Vertices points) const
virtual

Extract end points from the points on the lines.

Definition at line 173 of file line.cpp.

Line::Ptr jsk_recognition_utils::Line::flip ( )
virtual

@ brief flip direction of line.

Definition at line 120 of file line.cpp.

void jsk_recognition_utils::Line::foot ( const Eigen::Vector3f &  point,
Eigen::Vector3f &  output 
) const
virtual

compute a point which gives perpendicular projection.

Reimplemented in jsk_recognition_utils::Segment.

Definition at line 69 of file line.cpp.

Line::Ptr jsk_recognition_utils::Line::fromCoefficients ( const std::vector< float > &  coefficients)
static

Instantiate Line from array of float.

Definition at line 143 of file line.cpp.

void jsk_recognition_utils::Line::getDirection ( Eigen::Vector3f &  output) const
virtual

get normalized direction vector of the line and assign it to output.

Definition at line 49 of file line.cpp.

Eigen::Vector3f jsk_recognition_utils::Line::getDirection ( ) const
virtual

get normalized direction vector of the line.

Definition at line 54 of file line.cpp.

void jsk_recognition_utils::Line::getOrigin ( Eigen::Vector3f &  output) const
virtual

get origin of the line and assing it to output.

Definition at line 59 of file line.cpp.

Eigen::Vector3f jsk_recognition_utils::Line::getOrigin ( ) const
virtual

get origin of the line.

Definition at line 64 of file line.cpp.

bool jsk_recognition_utils::Line::isParallel ( const Line other,
double  angle_threshold = 0.1 
) const
virtual

return true if given line is parallel. angle_threshold is error tolerance.

Definition at line 105 of file line.cpp.

bool jsk_recognition_utils::Line::isPerpendicular ( const Line other,
double  angle_threshold = 0.1 
) const
virtual

return true if given line is perpendicular. angle_threshold is error tolerance.

Definition at line 110 of file line.cpp.

bool jsk_recognition_utils::Line::isSameDirection ( const Line other) const
virtual

@ brief Return true if given line is towards the same direction.

Definition at line 115 of file line.cpp.

Line::Ptr jsk_recognition_utils::Line::midLine ( const Line other) const
virtual

compute a middle line between given line.

Definition at line 126 of file line.cpp.

void jsk_recognition_utils::Line::parallelLineNormal ( const Line other,
Eigen::Vector3f &  output 
) const
virtual

compute a perpendicular line of two lines from origin_

Definition at line 135 of file line.cpp.

Line::Ptr jsk_recognition_utils::Line::parallelLineOnAPoint ( const Eigen::Vector3f &  p) const
virtual

compute a line on a point, whose direction is same to the current line.

Definition at line 162 of file line.cpp.

void jsk_recognition_utils::Line::point ( double  alpha,
Eigen::Vector3f &  ouptut 
)
virtual

Compute a point on normal from alpha parameter.

Definition at line 201 of file line.cpp.

void jsk_recognition_utils::Line::print ( )
virtual

Print Line information.

Definition at line 195 of file line.cpp.

Member Data Documentation

Eigen::Vector3f jsk_recognition_utils::Line::direction_
protected

Definition at line 196 of file line.h.

Eigen::Vector3f jsk_recognition_utils::Line::origin_
protected

Definition at line 197 of file line.h.


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


jsk_recognition_utils
Author(s):
autogenerated on Mon May 3 2021 03:03:03