Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef JSK_RECOGNITION_UTILS_GEO_LINE_H_
00037 #define JSK_RECOGNITION_UTILS_GEO_LINE_H_
00038
00039 #include <Eigen/Geometry>
00040 #include <boost/shared_ptr.hpp>
00041 #include "jsk_recognition_utils/types.h"
00042
00043 namespace jsk_recognition_utils
00044 {
00049 class Line
00050 {
00051 public:
00052 typedef boost::shared_ptr<Line> Ptr;
00053
00061 Line(const Eigen::Vector3f& direction, const Eigen::Vector3f& origin);
00062
00067 virtual void getDirection(Eigen::Vector3f& output) const;
00068
00073 virtual Eigen::Vector3f getDirection() const;
00074
00079 virtual void getOrigin(Eigen::Vector3f& output) const;
00080
00085 virtual Eigen::Vector3f getOrigin() const;
00086
00091 virtual double distanceToPoint(const Eigen::Vector3f& from) const;
00092
00097 virtual double distanceToPoint(const Eigen::Vector3f& from,
00098 Eigen::Vector3f& foot) const;
00099
00104 virtual double distance(const Line& other) const;
00105
00110 virtual void foot(const Eigen::Vector3f& point, Eigen::Vector3f& output) const;
00111
00116 virtual double angle(const Line& other) const;
00117
00123 virtual bool isParallel(const Line& other, double angle_threshold = 0.1) const;
00124
00130 virtual bool isPerpendicular(const Line& other, double angle_threshold = 0.1) const;
00131
00136 virtual Ptr midLine(const Line& other) const;
00137
00143 virtual Ptr parallelLineOnAPoint(const Eigen::Vector3f& p) const;
00144
00149 virtual PointPair findEndPoints(const Vertices& points) const;
00150
00158 virtual double computeAlpha(const Point& p) const;
00159
00164 virtual bool isSameDirection(const Line& other) const;
00165
00170 virtual Line::Ptr flip();
00171
00176 virtual void parallelLineNormal(const Line& other, Eigen::Vector3f& output) const;
00177
00182 static Ptr fromCoefficients(const std::vector<float>& coefficients);
00183
00188 virtual void print();
00189
00194 virtual void point(double alpha, Eigen::Vector3f& ouptut);
00195 protected:
00196 Eigen::Vector3f direction_;
00197 Eigen::Vector3f origin_;
00198 private:
00199 };
00200
00201 }
00202
00203 #endif