36 #define BOOST_PARAMETER_MAX_ARITY 7 43 Line(to - from, from), to_(to), length_((to - from).norm())
60 void Segment::foot(
const Eigen::Vector3f& from, Eigen::Vector3f& output)
const 62 Eigen::Vector3f foot_point;
78 Eigen::Vector3f foot_point;
83 Eigen::Vector3f& foot_point)
const 85 foot(point, foot_point);
86 return (foot_point - point).norm();
94 return 0 <= r && r <= 1.0;
105 <<
"[" << seg.
to_[0] <<
", " << seg.
to_[1] <<
", " << seg.
to_[2] <<
"]";
119 Eigen::Vector3f& foot_point,
120 double &distance_to_goal)
const 124 if (alpha >= 0 && alpha <=
length_) {
127 distance_to_goal =
length_ - alpha;
128 }
else if (alpha < 0) {
134 distance_to_goal = 0;
136 return (from - foot_point).norm();
152 marker.type = visualization_msgs::Marker::ARROW;
154 geometry_msgs::Point st;
155 geometry_msgs::Point ed;
163 marker.points.push_back(st);
164 marker.points.push_back(ed);
166 marker.scale.x = 0.012;
167 marker.scale.y = 0.02;
176 Eigen::Vector3f ln_origin = ln.
getOrigin();
178 Eigen::Vector3f v12 = (ln_origin -
origin_);
180 if (fabs(n1n2) < 1e-20) {
183 double alp1 = (ln_direction.dot(v12) - (n1n2 *
direction_.dot(v12))) / (1 - n1n2 * n1n2);
184 double alp2 = ((n1n2 * ln_direction.dot(v12)) -
direction_.dot(v12)) / (1 - n1n2 * n1n2);
187 alp2 >= 0 && alp2 <=
length_) {
188 Eigen::Vector3f p1 = alp1 * ln_direction + ln_origin;
190 if ((p1 - p2).norm() < distance_threshold) {
202 Eigen::Vector3f ln_origin = ln.
getOrigin();
204 Eigen::Vector3f v12 = (ln_origin -
origin_);
206 if (fabs(n1n2) < 1e-20) {
209 double alp1 = (ln_direction.dot(v12) - (n1n2 *
direction_.dot(v12))) / (1 - n1n2 * n1n2);
210 double alp2 = ((n1n2 * ln_direction.dot(v12)) -
direction_.dot(v12)) / (1 - n1n2 * n1n2);
212 if (alp1 >= 0 && alp1 <= ln.
length() &&
213 alp2 >= 0 && alp2 <=
length_) {
214 Eigen::Vector3f p1 = alp1 * ln_direction + ln_origin;
216 if ((p1 - p2).norm() < distance_threshold) {
virtual double distanceWithInfo(const Eigen::Vector3f &from, Eigen::Vector3f &foot_point, double &distance_to_goal) const
compute a distance to a point
virtual double distance(const Eigen::Vector3f &point) const
virtual void foot(const Eigen::Vector3f &point, Eigen::Vector3f &output) const
compute a point which gives perpendicular projection.
virtual double computeAlpha(const Point &p) const
virtual bool intersect(Plane &plane, Eigen::Vector3f &point) const
virtual void getOrigin(Eigen::Vector3f &output) const
get origin of the line and assing it to output.
Segment(const Eigen::Vector3f &from, const Eigen::Vector3f to)
Construct a line from a start point and a goal point.
virtual void point(double alpha, Eigen::Vector3f &ouptut)
Compute a point on normal from alpha parameter.
Eigen::Vector3f direction_
Class to represent 3-D straight line which has finite length.
virtual void getDirection(Eigen::Vector3f &output) const
get normalized direction vector of the line and assign it to output.
void toMarker(visualization_msgs::Marker &marker) const
make marker message to display the finite line
virtual Eigen::Vector3f getEnd() const
virtual void foot(const Eigen::Vector3f &point, Eigen::Vector3f &output) const
compute a point which gives perpendicular projection.
virtual void midpoint(Eigen::Vector3f &midpoint) const
virtual double dividingRatio(const Eigen::Vector3f &point) const
virtual bool isCross(const Line &ln, double distance_threshold=1e-5) const
is crossing with another line
friend std::ostream & operator<<(std::ostream &os, const Segment &seg)
virtual Segment::Ptr flipSegment() const
return flipped line (line of opposite direction)
virtual double length() const
return length of the line
Class to represent 3-D straight line.
virtual Eigen::Vector3f getNormal()