36 #define BOOST_PARAMETER_MAX_ARITY 7 43 Line::Line(
const Eigen::Vector3f& direction,
const Eigen::Vector3f& origin)
44 : direction_ (direction.
normalized()), origin_(origin)
76 const Eigen::Vector3f& from, Eigen::Vector3f& foot_point)
const 78 foot(from, foot_point);
79 return (from - foot_point).norm();
84 Eigen::Vector3f foot_point;
95 double theta =
acos(dot);
96 if (theta > M_PI / 2.0) {
97 return M_PI / 2.0 - theta;
107 return angle(other) < angle_threshold;
112 return (M_PI / 2.0 -
angle(other)) < angle_threshold;
129 Eigen::Vector3f new_origin;
138 Eigen::Vector3f foot_point;
145 Eigen::Vector3f
p(coefficients[0],
148 Eigen::Vector3f
d(coefficients[3],
159 return fabs(n.dot(v12)) / n.norm();
175 double min_alpha = DBL_MAX;
176 double max_alpha = - DBL_MAX;
177 Point min_alpha_point, max_alpha_point;
178 for (
size_t i = 0; i < points.size(); i++) {
181 if (alpha > max_alpha) {
185 if (alpha < min_alpha) {
192 return boost::make_tuple<Point, Point>(min_alpha_point, max_alpha_point);
virtual double distance(const Line &other) const
compute a distance to line.
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
virtual void print()
Print Line information.
virtual void point(double alpha, Eigen::Vector3f &ouptut)
Compute a point on normal from alpha parameter.
virtual PointPair findEndPoints(const Vertices &points) const
Extract end points from the points on the lines.
Eigen::Vector3f direction_
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
TFSIMD_FORCE_INLINE Vector3 normalized() const
virtual Ptr midLine(const Line &other) const
compute a middle line between given line.
virtual Eigen::Vector3f getOrigin() const
get origin of the line.
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 double distanceToPoint(const Eigen::Vector3f &from) const
compute a distance to a point
static Ptr fromCoefficients(const std::vector< float > &coefficients)
Instantiate Line from array of float.
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
virtual Ptr parallelLineOnAPoint(const Eigen::Vector3f &p) const
compute a line on a point, whose direction is same to the current line.
Line(const Eigen::Vector3f &direction, const Eigen::Vector3f &origin)
Construct a line from direction vector and a point on the line.
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
boost::tuple< Point, Point > PointPair
virtual bool isSameDirection(const Line &other) const
virtual Eigen::Vector3f getDirection() const
get normalized direction vector of the line.
Class to represent 3-D straight 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 void parallelLineNormal(const Line &other, Eigen::Vector3f &output) const
compute a perpendicular line of two lines from origin_