Go to the documentation of this file.
36 #ifndef JSK_RECOGNITION_UTILS_GEO_LINE_H_
37 #define JSK_RECOGNITION_UTILS_GEO_LINE_H_
39 #include <Eigen/Geometry>
40 #include <boost/shared_ptr.hpp>
61 Line(
const Eigen::Vector3f& direction,
const Eigen::Vector3f& origin);
67 virtual void getDirection(Eigen::Vector3f& output)
const;
79 virtual void getOrigin(Eigen::Vector3f& output)
const;
85 virtual Eigen::Vector3f
getOrigin()
const;
98 Eigen::Vector3f&
foot)
const;
110 virtual void foot(
const Eigen::Vector3f&
point, Eigen::Vector3f& output)
const;
123 virtual bool isParallel(
const Line& other,
double angle_threshold = 0.1)
const;
188 virtual void print();
194 virtual void point(
double alpha, Eigen::Vector3f& ouptut);
Line(const Eigen::Vector3f &direction, const Eigen::Vector3f &origin)
Construct a line from direction vector and a point on 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 double distance(const Line &other) const
compute a distance to line.
virtual bool isSameDirection(const Line &other) const
Eigen::Vector3f direction_
virtual void print()
Print Line information.
virtual PointPair findEndPoints(const Vertices &points) const
Extract end points from the points on the lines.
static Ptr fromCoefficients(const std::vector< float > &coefficients)
Instantiate Line from array of float.
virtual Ptr parallelLineOnAPoint(const Eigen::Vector3f &p) const
compute a line on a point, whose direction is same to the current line.
virtual void parallelLineNormal(const Line &other, Eigen::Vector3f &output) const
compute a perpendicular line of two lines from origin_
virtual Eigen::Vector3f getOrigin() const
get origin of the line.
virtual double distanceToPoint(const Eigen::Vector3f &from) const
compute a distance to a point
virtual void foot(const Eigen::Vector3f &point, Eigen::Vector3f &output) const
compute a point which gives perpendicular projection.
virtual double angle(const Line &other) const
compute angle between a given line.
virtual double computeAlpha(const Point &p) const
boost::shared_ptr< Line > Ptr
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 void point(double alpha, Eigen::Vector3f &ouptut)
Compute a point on normal from alpha parameter.
Class to represent 3-D straight line.
virtual Eigen::Vector3f getDirection() const
get normalized direction vector of the line.
boost::tuple< Point, Point > PointPair
virtual Ptr midLine(const Line &other) const
compute a middle line between given line.
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices