segment.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, <copyright holder> <email>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the name of the <organization> nor the
13  * names of its contributors may be used to endorse or promote products
14  * derived from this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY <copyright holder> <email> ''AS IS'' AND ANY
17  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  * DISCLAIMED. IN NO EVENT SHALL <copyright holder> <email> BE LIABLE FOR ANY
20  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26  *
27  */
28 
29 #ifndef SEGMENT_H
30 #define SEGMENT_H
31 
32 #include <ros/ros.h>
33 #include <eigen3/Eigen/Dense>
34 
35 namespace tuw_graph
36 {
37  class Segment
38  {
39  public:
45  Segment(const std::vector<Eigen::Vector2d> &_path, const float _min_space);
52  Segment(const uint32_t _id, const std::vector<Eigen::Vector2d> &_points, const float _min_space);
53 
58  void addPredecessor(const uint32_t _predecessor);
63  void addSuccessor(const uint32_t _successor);
68  std::vector<Eigen::Vector2d> getPath() const;
73  void setPath(const std::vector<Eigen::Vector2d> &_path);
78  float getMinPathSpace() const;
83  void setMinPathSpace(const float _space);
88  int getLength() const;
94  bool containsPredecessor(const uint32_t _predecessor);
100  bool containsSuccessor(const uint32_t _successor);
104  static void resetId();
105 
110  const Eigen::Vector2d &getStart() const;
115  const Eigen::Vector2d &getEnd() const;
116 
121  void setStart(const Eigen::Vector2d &_pt);
126  void setEnd(const Eigen::Vector2d &_pt);
127 
132  uint32_t getId() const;
137  void setId(const uint32_t _id);
142  const std::vector<uint32_t> &getPredecessors() const;
147  const std::vector<uint32_t> &getSuccessors() const;
148 
153  void cleanNeighbors(uint32_t _id);
158  void decreaseNeighborIdAbove(uint32_t _id);
163  bool &getOptStart();
168  bool &getOptEnd();
169 
170  private:
171  Eigen::Vector2d start_, end_;
172  float min_space_;
173  float length_;
174  std::vector<Eigen::Vector2d> wayPoints_;
175 
176  std::vector<uint32_t> predecessor_;
177  std::vector<uint32_t> successor_;
178 
179  static uint32_t static_id_;
180  uint32_t id_;
181 
184 
185  };
186 }
187 #endif // PLANNER_NODE_H
std::vector< uint32_t > successor_
Definition: segment.h:177
bool optimizedStart_
Definition: segment.h:182
void addPredecessor(const uint32_t _predecessor)
adds a predecessor to the object
Definition: segment.cpp:77
uint32_t getId() const
returns the id
Definition: segment.cpp:128
Segment(const std::vector< Eigen::Vector2d > &_path, const float _min_space)
constructor
Definition: segment.cpp:85
static void resetId()
resets the id counter (which is used to generate uinique ids)
Definition: segment.cpp:182
void setPath(const std::vector< Eigen::Vector2d > &_path)
sets a new path of the robot
Definition: segment.cpp:192
void setEnd(const Eigen::Vector2d &_pt)
sets endpoint
Definition: segment.cpp:118
Eigen::Vector2d end_
Definition: segment.h:171
static uint32_t static_id_
Definition: segment.h:179
float getMinPathSpace() const
returns the minimum space in a segment
Definition: segment.cpp:203
const Eigen::Vector2d & getEnd() const
returns const ref to endpoint
Definition: segment.cpp:138
bool containsPredecessor(const uint32_t _predecessor)
checks if the segment has a predecessor with id _predecessor
Definition: segment.cpp:158
bool containsSuccessor(const uint32_t _successor)
checks if the segment has a predecessor with id _successor
Definition: segment.cpp:170
void decreaseNeighborIdAbove(uint32_t _id)
decreases the id and all neighbor ids above or equal _id by one (needed to safely remove entities) ...
Definition: segment.cpp:55
bool & getOptEnd()
returns a reference to opt end used to save if a segment was allready optimized
Definition: segment.cpp:223
void setMinPathSpace(const float _space)
sets the minimum space of a segment
Definition: segment.cpp:208
void cleanNeighbors(uint32_t _id)
removing all predecessors or successors with id
Definition: segment.cpp:36
void setId(const uint32_t _id)
set the id
Definition: segment.cpp:133
void addSuccessor(const uint32_t _successor)
adds a successor to the object
Definition: segment.cpp:81
void setStart(const Eigen::Vector2d &_pt)
sets the startpoint
Definition: segment.cpp:111
uint32_t id_
Definition: segment.h:180
std::vector< uint32_t > predecessor_
Definition: segment.h:176
std::vector< Eigen::Vector2d > getPath() const
returns the path
Definition: segment.cpp:187
int getLength() const
returns the length of the path
Definition: segment.cpp:213
const Eigen::Vector2d & getStart() const
returns const ref to startpoint
Definition: segment.cpp:143
const std::vector< uint32_t > & getSuccessors() const
returns a const reference to the successor
Definition: segment.cpp:153
std::vector< Eigen::Vector2d > wayPoints_
Definition: segment.h:174
bool & getOptStart()
returns a reference to opt start used to save if a segment was allready optimized ...
Definition: segment.cpp:218
Eigen::Vector2d start_
Definition: segment.h:171
const std::vector< uint32_t > & getPredecessors() const
returns a const reference to the predecessors
Definition: segment.cpp:148


tuw_voronoi_graph
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:44