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

Class to represent 3-D straight line which has finite length. More...

#include <segment.h>

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

Public Types

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

Public Member Functions

virtual double distance (const Eigen::Vector3f &point) const
 
virtual double distance (const Eigen::Vector3f &point, Eigen::Vector3f &foot_point) const
 
virtual double distanceWithInfo (const Eigen::Vector3f &from, Eigen::Vector3f &foot_point, double &distance_to_goal) const
 compute a distance to a point More...
 
virtual double dividingRatio (const Eigen::Vector3f &point) const
 
virtual Segment::Ptr flipSegment () const
 return flipped line (line of opposite direction) More...
 
virtual void foot (const Eigen::Vector3f &point, Eigen::Vector3f &output) const
 compute a point which gives perpendicular projection. More...
 
virtual void getEnd (Eigen::Vector3f &output) const
 get end of the line and assing it to output. More...
 
virtual Eigen::Vector3f getEnd () const
 
virtual bool intersect (Plane &plane, Eigen::Vector3f &point) const
 
virtual bool isCross (const Line &ln, double distance_threshold=1e-5) const
 is crossing with another line More...
 
virtual bool isCross (const Segment &ln, double distance_threshold=1e-5) const
 
virtual double length () const
 return length of the line More...
 
virtual void midpoint (Eigen::Vector3f &midpoint) const
 
 Segment (const Eigen::Vector3f &from, const Eigen::Vector3f to)
 Construct a line from a start point and a goal point. More...
 
void toMarker (visualization_msgs::Marker &marker) const
 make marker message to display the finite line More...
 
- 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 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

double length_
 
Eigen::Vector3f to_
 
- Protected Attributes inherited from jsk_recognition_utils::Line
Eigen::Vector3f direction_
 
Eigen::Vector3f origin_
 

Friends

std::ostream & operator<< (std::ostream &os, const Segment &seg)
 

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 straight line which has finite length.

Definition at line 50 of file segment.h.

Member Typedef Documentation

Definition at line 53 of file segment.h.

Constructor & Destructor Documentation

jsk_recognition_utils::Segment::Segment ( const Eigen::Vector3f &  from,
const Eigen::Vector3f  to 
)

Construct a line from a start point and a goal point.

Parameters
from
to

Definition at line 42 of file segment.cpp.

Member Function Documentation

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

Definition at line 76 of file segment.cpp.

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

Definition at line 82 of file segment.cpp.

double jsk_recognition_utils::Segment::distanceWithInfo ( const Eigen::Vector3f &  from,
Eigen::Vector3f &  foot_point,
double &  distance_to_goal 
) const
virtual

compute a distance to a point

Parameters
from
foot_point
distance_to_goal

Definition at line 118 of file segment.cpp.

double jsk_recognition_utils::Segment::dividingRatio ( const Eigen::Vector3f &  point) const
virtual

Definition at line 47 of file segment.cpp.

Segment::Ptr jsk_recognition_utils::Segment::flipSegment ( ) const
virtual

return flipped line (line of opposite direction)

Definition at line 139 of file segment.cpp.

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

compute a point which gives perpendicular projection.

Reimplemented from jsk_recognition_utils::Line.

Definition at line 60 of file segment.cpp.

void jsk_recognition_utils::Segment::getEnd ( Eigen::Vector3f &  output) const
virtual

get end of the line and assing it to output.

Definition at line 108 of file segment.cpp.

Eigen::Vector3f jsk_recognition_utils::Segment::getEnd ( ) const
virtual

Definition at line 113 of file segment.cpp.

bool jsk_recognition_utils::Segment::intersect ( Plane plane,
Eigen::Vector3f &  point 
) const
virtual

Definition at line 89 of file segment.cpp.

bool jsk_recognition_utils::Segment::isCross ( const Line ln,
double  distance_threshold = 1e-5 
) const
virtual

is crossing with another line

Definition at line 174 of file segment.cpp.

bool jsk_recognition_utils::Segment::isCross ( const Segment ln,
double  distance_threshold = 1e-5 
) const
virtual

Definition at line 200 of file segment.cpp.

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

return length of the line

Definition at line 145 of file segment.cpp.

void jsk_recognition_utils::Segment::midpoint ( Eigen::Vector3f &  midpoint) const
virtual

Definition at line 97 of file segment.cpp.

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

make marker message to display the finite line

Definition at line 150 of file segment.cpp.

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  os,
const Segment seg 
)
friend

Definition at line 102 of file segment.cpp.

Member Data Documentation

double jsk_recognition_utils::Segment::length_
protected

Definition at line 118 of file segment.h.

Eigen::Vector3f jsk_recognition_utils::Segment::to_
protected

Definition at line 117 of file segment.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