router.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 ROUTER_H
30 #define ROUTER_H
31 
32 #include <vector>
33 #include <memory>
34 #include <opencv2/core/core.hpp>
38 
39 namespace multi_robot_router
40 {
41 class Router
42 {
43  public:
44  Router(const uint32_t _nr_robots);
45  Router();
46 
50  void resize(const uint32_t _nr_robots);
60  bool makePlan(const std::vector<Eigen::Vector3d> &_starts, const std::vector<Eigen::Vector3d> &_goals, const std::vector<float> &_radius, const cv::Mat &_map, const float &_resolution, const Eigen::Vector2d &_origin, const std::vector<Segment> &_graph, const std::vector<std::string> &_robot_names);
69  const std::vector<Checkpoint> &getRoute(const uint32_t _robot) const;
74  uint32_t getDuration_ms() const;
79  float getOverallPathLength() const;
84  float getLongestPathLength() const;
89  uint32_t getPriorityScheduleAttemps() const;
94  uint32_t getSpeedScheduleAttemps() const;
95 
96  std::shared_ptr<float> potential_;
97 
98  private:
99  //find the right segments to start from
100  bool calculateStartPoints(const std::vector<float> &_radius, const cv::Mat &_map, const float &resolution, const Eigen::Vector2d &origin, const std::vector<Segment> &_graph);
101  //Find the segment if the graph is a voronoi one
102  int32_t getSegment(const std::vector<Segment> &_graph, const Eigen::Vector2d &_pose) const;
103  //Helper dist calculation
104  float distanceToSegment(const Segment &_s, const Eigen::Vector2d &_p) const;
105  //Checks if _seg is a leave of the graph and uses the closes neighbor as segment if the width of the leave is to small
106  bool resolveSegment(const std::vector<Segment> &_graph, const uint32_t &_segId, const Eigen::Vector2d &_originPoint, const float &_radius, uint32_t &_foundSeg) const;
107  //for every path remove the first and last "segmentOptimizations_" number of segments if possible
108  void optimizePaths(const std::vector<Segment> &_graph);
109  //adds start and endpoints to the path
111  //Preprocessing endpoints for enpoint calculation threaded
112  bool preprocessEndpoints(const std::vector<float> &_radius, const float &resolution, const Eigen::Vector2d &origin, const std::vector<Segment> &_graph);
113  //Calculate endpoints
114  bool processEndpointsExpander(const cv::Mat &_map, const std::vector<Segment> &_graph, const Eigen::Vector2d &_realStart, const Eigen::Vector2d &_realGoal, Eigen::Vector2d &_voronoiStart, Eigen::Vector2d &_voronoiGoal, uint32_t &_segmentStart, uint32_t &_segmentGoal, const uint32_t _diameter, const uint32_t _index) const;
115 
116  uint32_t robot_nr_;
117  std::vector<Eigen::Vector3d> starts_;
118  std::vector<Eigen::Vector3d> goals_;
119  std::vector<Eigen::Vector2d> realGoals_;
120  std::vector<Eigen::Vector2d> realStart_;
121  std::vector<Eigen::Vector2d> voronoiGoals_;
122  std::vector<Eigen::Vector2d> voronoiStart_;
123  std::vector<uint32_t> startSegments_;
124  std::vector<uint32_t> goalSegments_;
125  std::vector<std::string> robot_names_;
126 
131  std::vector<std::vector<Checkpoint>> routingTable_;
134  uint32_t duration_;
135 
136  protected:
137  enum class goalMode
138  {
142  };
143  enum class graphType
144  {
145  voronoi,
146  random
147  };
148  enum class routerType
149  {
150  singleThread,
152  };
155  float routerTimeLimit_s_ = 10.0;
156  bool segmentOptimizations_ = false;
157  bool speedRescheduling_ = true;
159  bool collisionResolver_ = true;
160 
161  void setPlannerType(routerType _type, uint32_t _nr_threads);
162 };
163 } // namespace multi_robot_router
164 #endif // PLANNER_H
multi_robot_router::Router::routerTimeLimit_s_
float routerTimeLimit_s_
Definition: router.h:155
multi_robot_router::Router::getOverallPathLength
float getOverallPathLength() const
getter
Definition: router.cpp:474
multi_robot_router::Router::goalSegments_
std::vector< uint32_t > goalSegments_
Definition: router.h:124
multi_robot_router::Router::setPlannerType
void setPlannerType(routerType _type, uint32_t _nr_threads)
Definition: router.cpp:59
multi_robot_router::Router::getSpeedScheduleAttemps
uint32_t getSpeedScheduleAttemps() const
getter
Definition: router.cpp:484
multi_robot_router::Router::potential_
std::shared_ptr< float > potential_
Definition: router.h:96
multi_robot_router::Router::getDuration_ms
uint32_t getDuration_ms() const
getter
Definition: router.cpp:464
multi_robot_router::Router::multiRobotRouter_
MultiRobotRouter * multiRobotRouter_
Definition: router.h:128
multi_robot_router::Router::getRoute
const std::vector< Checkpoint > & getRoute(const uint32_t _robot) const
returns the found Routing Table
Definition: router.cpp:459
point_expander.h
multi_robot_router::Router::goals_
std::vector< Eigen::Vector3d > goals_
Definition: router.h:118
multi_robot_router::Router::goalMode::use_voronoi_goal
@ use_voronoi_goal
multi_robot_router::Router::segmentOptimizations_
bool segmentOptimizations_
Definition: router.h:156
multi_robot_router::Router::getSegment
int32_t getSegment(const std::vector< Segment > &_graph, const Eigen::Vector2d &_pose) const
Definition: router.cpp:237
multi_robot_router::Router::goalMode_
goalMode goalMode_
Definition: router.h:154
multi_robot_router::Router::graphType
graphType
Definition: router.h:143
multi_robot_router::Router::setCollisionResolutionType
void setCollisionResolutionType(const SegmentExpander::CollisionResolverType _cr)
sets the CollisionResolverType used
Definition: router.cpp:54
multi_robot_router::Router::graphType::voronoi
@ voronoi
multi_robot_router::SegmentExpander::CollisionResolverType
CollisionResolverType
Definition: segment_expander.h:48
multi_robot_router::MultiRobotRouter
standard multi robot router without multi threading (Works best in practice)
Definition: multi_robot_router.h:47
multi_robot_router::Router::preprocessEndpoints
bool preprocessEndpoints(const std::vector< float > &_radius, const float &resolution, const Eigen::Vector2d &origin, const std::vector< Segment > &_graph)
Definition: router.cpp:83
multi_robot_router::Router::starts_
std::vector< Eigen::Vector3d > starts_
Definition: router.h:117
multi_robot_router::Router::realStart_
std::vector< Eigen::Vector2d > realStart_
Definition: router.h:120
multi_robot_router.h
multi_robot_router::Router::mrrTs_
MultiRobotRouterThreadedSrr mrrTs_
Definition: router.h:130
multi_robot_router::Router::goalMode::use_segment_goal
@ use_segment_goal
multi_robot_router::Router::longestPatLength_
float longestPatLength_
Definition: router.h:133
multi_robot_router::Router::makePlan
bool makePlan(const std::vector< Eigen::Vector3d > &_starts, const std::vector< Eigen::Vector3d > &_goals, const std::vector< float > &_radius, const cv::Mat &_map, const float &_resolution, const Eigen::Vector2d &_origin, const std::vector< Segment > &_graph, const std::vector< std::string > &_robot_names)
generates the plan from (Vertex[odom robotPose] to Vertex[_goals]
Definition: router.cpp:328
multi_robot_router::Router::startSegments_
std::vector< uint32_t > startSegments_
Definition: router.h:123
multi_robot_router::Router::realGoals_
std::vector< Eigen::Vector2d > realGoals_
Definition: router.h:119
multi_robot_router::Router::overallPathLength_
float overallPathLength_
Definition: router.h:132
multi_robot_router::MultiRobotRouterThreadedSrr
Definition: multi_robot_router_threaded_srr.h:43
multi_robot_router::Router::goalMode::use_map_goal
@ use_map_goal
multi_robot_router::Router::voronoiGoals_
std::vector< Eigen::Vector2d > voronoiGoals_
Definition: router.h:121
multi_robot_router::Router::pointExpander_
PointExpander pointExpander_
with the robot id one can access the robot name
Definition: router.h:127
multi_robot_router::Router::graphType::random
@ random
multi_robot_router::Router::collisionResolver_
bool collisionResolver_
Definition: router.h:159
multi_robot_router::Router::priorityRescheduling_
bool priorityRescheduling_
Definition: router.h:158
multi_robot_router::Router::resize
void resize(const uint32_t _nr_robots)
resizes the planner to a different nr of _nr_robots
Definition: router.cpp:67
multi_robot_router::Router::resolveSegment
bool resolveSegment(const std::vector< Segment > &_graph, const uint32_t &_segId, const Eigen::Vector2d &_originPoint, const float &_radius, uint32_t &_foundSeg) const
Definition: router.cpp:280
multi_robot_router::Router::duration_
uint32_t duration_
Definition: router.h:134
multi_robot_router::Router::robot_nr_
uint32_t robot_nr_
Definition: router.h:116
multi_robot_router::Router::graphMode_
graphType graphMode_
Definition: router.h:153
multi_robot_router::Router::routerType::multiThreadSrr
@ multiThreadSrr
multi_robot_router::Router::speedRescheduling_
bool speedRescheduling_
Definition: router.h:157
multi_robot_router::Router::Router
Router()
Definition: router.cpp:40
multi_robot_router::Router::postprocessRoutingTable
void postprocessRoutingTable()
Definition: router.cpp:426
multi_robot_router_threaded_srr.h
multi_robot_router::Router::routingTable_
std::vector< std::vector< Checkpoint > > routingTable_
Definition: router.h:131
multi_robot_router::Router::getLongestPathLength
float getLongestPathLength() const
getter
Definition: router.cpp:469
multi_robot_router::Router::routerType::singleThread
@ singleThread
multi_robot_router::Router::optimizePaths
void optimizePaths(const std::vector< Segment > &_graph)
Definition: router.cpp:414
multi_robot_router::PointExpander
Definition: point_expander.h:43
multi_robot_router::Router
Definition: router.h:41
multi_robot_router::Segment
Definition: srr_utils.h:41
multi_robot_router::Router::mrr_
MultiRobotRouter mrr_
Definition: router.h:129
multi_robot_router::Router::processEndpointsExpander
bool processEndpointsExpander(const cv::Mat &_map, const std::vector< Segment > &_graph, const Eigen::Vector2d &_realStart, const Eigen::Vector2d &_realGoal, Eigen::Vector2d &_voronoiStart, Eigen::Vector2d &_voronoiGoal, uint32_t &_segmentStart, uint32_t &_segmentGoal, const uint32_t _diameter, const uint32_t _index) const
Definition: router.cpp:110
multi_robot_router::Router::calculateStartPoints
bool calculateStartPoints(const std::vector< float > &_radius, const cv::Mat &_map, const float &resolution, const Eigen::Vector2d &origin, const std::vector< Segment > &_graph)
Definition: router.cpp:192
multi_robot_router::Router::getPriorityScheduleAttemps
uint32_t getPriorityScheduleAttemps() const
getter
Definition: router.cpp:479
multi_robot_router::Router::routerType
routerType
Definition: router.h:148
multi_robot_router
Definition: avoidance_resolution.h:37
multi_robot_router::Router::goalMode
goalMode
Definition: router.h:137
multi_robot_router::Router::robot_names_
std::vector< std::string > robot_names_
Definition: router.h:125
multi_robot_router::Router::voronoiStart_
std::vector< Eigen::Vector2d > voronoiStart_
Definition: router.h:122
multi_robot_router::Router::distanceToSegment
float distanceToSegment(const Segment &_s, const Eigen::Vector2d &_p) const
Definition: router.cpp:257


tuw_multi_robot_router
Author(s): Benjamin Binder
autogenerated on Wed Mar 2 2022 01:10:16