Class to represent 3-D straight line. More...
#include <line.h>
Public Types | |
typedef boost::shared_ptr< Line > | Ptr |
Public Member Functions | |
virtual double | angle (const Line &other) const |
compute angle between a given line. | |
virtual double | computeAlpha (const Point &p) const |
virtual double | distance (const Line &other) const |
compute a distance to line. | |
virtual double | distanceToPoint (const Eigen::Vector3f &from) const |
compute a distance to a point | |
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. | |
virtual PointPair | findEndPoints (const Vertices &points) const |
Extract end points from the points on the lines. | |
virtual Line::Ptr | flip () |
virtual void | foot (const Eigen::Vector3f &point, Eigen::Vector3f &output) const |
compute a point which gives perpendicular projection. | |
virtual void | getDirection (Eigen::Vector3f &output) const |
get normalized direction vector of the line and assign it to output. | |
virtual Eigen::Vector3f | getDirection () const |
get normalized direction vector of the line. | |
virtual void | getOrigin (Eigen::Vector3f &output) const |
get origin of the line and assing it to output. | |
virtual Eigen::Vector3f | getOrigin () const |
get origin of the line. | |
virtual bool | isParallel (const Line &other, double angle_threshold=0.1) const |
return true if given line is parallel. angle_threshold is error tolerance. | |
virtual bool | isPerpendicular (const Line &other, double angle_threshold=0.1) const |
return true if given line is perpendicular. angle_threshold is error tolerance. | |
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. | |
virtual Ptr | midLine (const Line &other) const |
compute a middle line between given line. | |
virtual void | parallelLineNormal (const Line &other, Eigen::Vector3f &output) const |
compute a perpendicular line of two lines from origin_ | |
virtual Ptr | parallelLineOnAPoint (const Eigen::Vector3f &p) const |
compute a line on a point, whose direction is same to the current line. | |
virtual void | point (double alpha, Eigen::Vector3f &ouptut) |
Compute a point on normal from alpha parameter. | |
virtual void | print () |
Print Line information. | |
Static Public Member Functions | |
static Ptr | fromCoefficients (const std::vector< float > &coefficients) |
Instantiate Line from array of float. | |
Protected Attributes | |
Eigen::Vector3f | direction_ |
Eigen::Vector3f | origin_ |
typedef boost::shared_ptr<Line> jsk_recognition_utils::Line::Ptr |
Reimplemented in jsk_recognition_utils::PolyLine, and jsk_recognition_utils::Segment.
jsk_recognition_utils::Line::Line | ( | const Eigen::Vector3f & | direction, |
const Eigen::Vector3f & | origin | ||
) |
double jsk_recognition_utils::Line::angle | ( | const Line & | other | ) | const [virtual] |
double jsk_recognition_utils::Line::computeAlpha | ( | const Point & | p | ) | const [virtual] |
double jsk_recognition_utils::Line::distance | ( | const Line & | other | ) | const [virtual] |
double jsk_recognition_utils::Line::distanceToPoint | ( | const Eigen::Vector3f & | from | ) | const [virtual] |
double jsk_recognition_utils::Line::distanceToPoint | ( | const Eigen::Vector3f & | from, |
Eigen::Vector3f & | foot | ||
) | const [virtual] |
PointPair jsk_recognition_utils::Line::findEndPoints | ( | const Vertices & | points | ) | const [virtual] |
Line::Ptr jsk_recognition_utils::Line::flip | ( | ) | [virtual] |
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.
Line::Ptr jsk_recognition_utils::Line::fromCoefficients | ( | const std::vector< float > & | coefficients | ) | [static] |
void jsk_recognition_utils::Line::getDirection | ( | Eigen::Vector3f & | output | ) | const [virtual] |
Eigen::Vector3f jsk_recognition_utils::Line::getDirection | ( | ) | const [virtual] |
void jsk_recognition_utils::Line::getOrigin | ( | Eigen::Vector3f & | output | ) | const [virtual] |
Eigen::Vector3f jsk_recognition_utils::Line::getOrigin | ( | ) | const [virtual] |
bool jsk_recognition_utils::Line::isParallel | ( | const Line & | other, |
double | angle_threshold = 0.1 |
||
) | const [virtual] |
bool jsk_recognition_utils::Line::isPerpendicular | ( | const Line & | other, |
double | angle_threshold = 0.1 |
||
) | const [virtual] |
bool jsk_recognition_utils::Line::isSameDirection | ( | const Line & | other | ) | const [virtual] |
Line::Ptr jsk_recognition_utils::Line::midLine | ( | const Line & | other | ) | const [virtual] |
void jsk_recognition_utils::Line::parallelLineNormal | ( | const Line & | other, |
Eigen::Vector3f & | output | ||
) | const [virtual] |
Line::Ptr jsk_recognition_utils::Line::parallelLineOnAPoint | ( | const Eigen::Vector3f & | p | ) | const [virtual] |
void jsk_recognition_utils::Line::point | ( | double | alpha, |
Eigen::Vector3f & | ouptut | ||
) | [virtual] |
void jsk_recognition_utils::Line::print | ( | ) | [virtual] |
Eigen::Vector3f jsk_recognition_utils::Line::direction_ [protected] |
Eigen::Vector3f jsk_recognition_utils::Line::origin_ [protected] |