polyline.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef JSK_RECOGNITION_UTILS_GEO_POLYLINE_H_
37 #define JSK_RECOGNITION_UTILS_GEO_POLYLINE_H_
38 
39 #include <Eigen/Geometry>
40 #include <boost/shared_ptr.hpp>
43 #include "visualization_msgs/Marker.h"
44 
45 namespace jsk_recognition_utils
46 {
51  class PolyLine : public Line
52  {
53  public:
61  PolyLine(const std::vector < Eigen::Vector3f > &points);
62 
69  virtual Segment::Ptr at(int index) const;
70 
75  virtual double distance(const Eigen::Vector3f& point,
76  Eigen::Vector3f& foot_point) const;
77  virtual double distance(const Eigen::Vector3f& point) const;
78 
83  virtual double distanceWithInfo(const Eigen::Vector3f& from,
84  Eigen::Vector3f& foot_point,
85  double& distance_to_goal,
86  int& foot_index,
87  double& foot_alpha) const;
88 
95  virtual void getDirection(int index, Eigen::Vector3f& output) const;
96  virtual Eigen::Vector3f getDirection(int index) const;
97 
102  virtual double length() const;
103 
108  virtual PolyLine::Ptr flipPolyLine() const;
109 
114  void toMarker(visualization_msgs::Marker& marker) const;
115 
116  friend std::ostream& operator<<(std::ostream& os, const PolyLine& pl);
117  protected:
118  std::vector< Segment::Ptr > segments;
119  };
120 }
121 
122 #endif
boost::shared_ptr
types.h
jsk_recognition_utils
Definition: color_utils.h:41
jsk_recognition_utils::PolyLine::distanceWithInfo
virtual double distanceWithInfo(const Eigen::Vector3f &from, Eigen::Vector3f &foot_point, double &distance_to_goal, int &foot_index, double &foot_alpha) const
compute a distance to a point, get various information
Definition: polyline.cpp:58
jsk_recognition_utils::Segment::Ptr
boost::shared_ptr< Segment > Ptr
Definition: segment.h:85
jsk_recognition_utils::PolyLine::PolyLine
PolyLine(const std::vector< Eigen::Vector3f > &points)
Construct a polyline from points. The polyline consists of lines which starts with p[i] and ends with...
Definition: polyline.cpp:43
jsk_recognition_utils::PolyLine::flipPolyLine
virtual PolyLine::Ptr flipPolyLine() const
Definition: polyline.cpp:121
jsk_recognition_utils::PolyLine::at
virtual Segment::Ptr at(int index) const
Definition: polyline.cpp:53
jsk_recognition_utils::PolyLine::toMarker
void toMarker(visualization_msgs::Marker &marker) const
Definition: polyline.cpp:127
jsk_recognition_utils::PolyLine::Ptr
boost::shared_ptr< PolyLine > Ptr
Definition: polyline.h:118
jsk_recognition_utils::PolyLine::distance
virtual double distance(const Eigen::Vector3f &point, Eigen::Vector3f &foot_point) const
compute a distance to a point
Definition: polyline.cpp:93
jsk_recognition_utils::PolyLine::segments
std::vector< Segment::Ptr > segments
Definition: polyline.h:182
jsk_recognition_utils::PolyLine
Class to represent 3-D polyline (not closed).
Definition: polyline.h:83
jsk_recognition_utils::PolyLine::operator<<
friend std::ostream & operator<<(std::ostream &os, const PolyLine &pl)
Definition: polyline.cpp:166
jsk_recognition_utils::Line::point
virtual void point(double alpha, Eigen::Vector3f &ouptut)
Compute a point on normal from alpha parameter.
Definition: line.cpp:201
jsk_recognition_utils::PolyLine::length
virtual double length() const
get total length of the polyline
Definition: polyline.cpp:112
jsk_recognition_utils::Line::getDirection
virtual Eigen::Vector3f getDirection() const
get normalized direction vector of the line.
Definition: line.cpp:54
segment.h


jsk_recognition_utils
Author(s):
autogenerated on Tue Jan 7 2025 04:04:52