Public Types | Public Member Functions | Protected Attributes | Friends | List of all members
jsk_recognition_utils::PolyLine Class Reference

Class to represent 3-D polyline (not closed). More...

#include <polyline.h>

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

Public Types

typedef boost::shared_ptr< PolyLinePtr
 
- Public Types inherited from jsk_recognition_utils::Line
typedef boost::shared_ptr< LinePtr
 

Public Member Functions

virtual Segment::Ptr at (int index) const
 
virtual double distance (const Eigen::Vector3f &point, Eigen::Vector3f &foot_point) const
 compute a distance to a point More...
 
virtual double distance (const Eigen::Vector3f &point) const
 
virtual double distanceWithInfo (const Eigen::Vector3f &from, Eigen::Vector3f &foot_point, double &distance_to_goal, int &foot_index, double &foot_alpha) const
 compute a distance to a point, get various information More...
 
virtual PolyLine::Ptr flipPolyLine () const
 
virtual void getDirection (int index, Eigen::Vector3f &output) const
 get normalized direction vector of the line. More...
 
virtual Eigen::Vector3f getDirection (int index) const
 
virtual double length () const
 get total length of the polyline More...
 
 PolyLine (const std::vector< Eigen::Vector3f > &points)
 Construct a polyline from points. The polyline consists of lines which starts with p[i] and ends with p[i+1]. More...
 
void toMarker (visualization_msgs::Marker &marker) const
 
- Public Member Functions inherited from jsk_recognition_utils::Line
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...
 

Protected Attributes

std::vector< Segment::Ptrsegments
 
- Protected Attributes inherited from jsk_recognition_utils::Line
Eigen::Vector3f direction_
 
Eigen::Vector3f origin_
 

Friends

std::ostream & operator<< (std::ostream &os, const PolyLine &pl)
 

Additional Inherited Members

- Static Public Member Functions inherited from jsk_recognition_utils::Line
static Ptr fromCoefficients (const std::vector< float > &coefficients)
 Instantiate Line from array of float. More...
 

Detailed Description

Class to represent 3-D polyline (not closed).

Definition at line 51 of file polyline.h.

Member Typedef Documentation

Definition at line 54 of file polyline.h.

Constructor & Destructor Documentation

jsk_recognition_utils::PolyLine::PolyLine ( const std::vector< Eigen::Vector3f > &  points)

Construct a polyline from points. The polyline consists of lines which starts with p[i] and ends with p[i+1].

Parameters
points

Definition at line 43 of file polyline.cpp.

Member Function Documentation

Segment::Ptr jsk_recognition_utils::PolyLine::at ( int  index) const
virtual

@ brief get the line positioned at index

Parameters
indexposition of the line

Definition at line 53 of file polyline.cpp.

double jsk_recognition_utils::PolyLine::distance ( const Eigen::Vector3f &  point,
Eigen::Vector3f &  foot_point 
) const
virtual

compute a distance to a point

Definition at line 93 of file polyline.cpp.

double jsk_recognition_utils::PolyLine::distance ( const Eigen::Vector3f &  point) const
virtual

Definition at line 85 of file polyline.cpp.

double jsk_recognition_utils::PolyLine::distanceWithInfo ( const Eigen::Vector3f &  from,
Eigen::Vector3f &  foot_point,
double &  distance_to_goal,
int &  foot_index,
double &  foot_alpha 
) const
virtual

compute a distance to a point, get various information

Definition at line 58 of file polyline.cpp.

PolyLine::Ptr jsk_recognition_utils::PolyLine::flipPolyLine ( ) const
virtual

@ brief flip direction of the polyline.

Definition at line 121 of file polyline.cpp.

void jsk_recognition_utils::PolyLine::getDirection ( int  index,
Eigen::Vector3f &  output 
) const
virtual

get normalized direction vector of the line.

Parameters
indexposition of the line which returns direction

Definition at line 101 of file polyline.cpp.

Eigen::Vector3f jsk_recognition_utils::PolyLine::getDirection ( int  index) const
virtual

Definition at line 105 of file polyline.cpp.

double jsk_recognition_utils::PolyLine::length ( ) const
virtual

get total length of the polyline

Definition at line 112 of file polyline.cpp.

void jsk_recognition_utils::PolyLine::toMarker ( visualization_msgs::Marker &  marker) const

@ brief make marker message to display the polyline

Definition at line 127 of file polyline.cpp.

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  os,
const PolyLine pl 
)
friend

Definition at line 166 of file polyline.cpp.

Member Data Documentation

std::vector< Segment::Ptr > jsk_recognition_utils::PolyLine::segments
protected

Definition at line 118 of file polyline.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