Multi-robot Playground
SearchAlgorithms.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020, Alysson Ribeiro da Silva
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  *
8  * 1. Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * 3. All advertising materials mentioning features or use of this software must
16  * display the following acknowledgement:
17  * This product includes software developed by Alysson Ribeiro da Silva.
18  *
19  * 4. Neither the name of the copyright holder nor the names of its
20  * contributors may be used to endorse or promote products derived from
21  * this software without specific prior written permission.
22  *
23  * 5. The source and the binary form, and any modifications made to them
24  * may not be used for the purpose of training or improving machine learning
25  * algorithms, including but not limited to artificial intelligence, natural
26  * language processing, or data mining. This condition applies to any derivatives,
27  * modifications, or updates based on the Software code. Any usage of the source
28  * or the binary form in an AI-training dataset is considered a breach of
29  * this License.
30  *
31  * THIS SOFTWARE IS PROVIDED BY COPYRIGHT HOLDER "AS IS" AND ANY EXPRESS OR
32  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
33  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
34  * EVENT SHALL COPYRIGHT HOLDER BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
35  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
36  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
37  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
38  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
39  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
40  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
41 */
42 
43 #ifndef SEARCH_ALGORITHMS_H
44 #define SEARCH_ALGORITHMS_H
45 
46 #include <stdio.h>
47 #include <cstring>
48 #include <cstdlib>
49 #include <iostream>
50 #include <exception>
51 #include <list>
52 #include <vector>
53 #include <limits>
54 #include "nav_msgs/OccupancyGrid.h"
55 #include "Common.h"
56 
57 namespace sa {
58  void InitOccFrom(nav_msgs::OccupancyGrid& rInput, nav_msgs::OccupancyGrid& rOutput);
59  bool IsInBounds(nav_msgs::OccupancyGrid& rInput, Vec2i& rPos);
60  bool CheckAny(nav_msgs::OccupancyGrid& rInput, const Vec2i& rStart, const Vec2i& rEnd, const int& rVal);
61  void ComputePath(nav_msgs::OccupancyGrid& rOcc,
62  const Vec2i& rStart,
63  const Vec2i& rEnd,
64  std::list<Vec2i>& rOutPath);
66  nav_msgs::OccupancyGrid& rInput,
67  const Vec2i& rStart,
68  const Vec2i& rEnd,
69  std::list<Vec2i>& rOutPath);
70  void ComputeFrontiers(nav_msgs::OccupancyGrid& rInput,
71  nav_msgs::OccupancyGrid& rOutput,
72  std::vector<Vec2i>& rFrontiers);
73  void ComputeClusters(nav_msgs::OccupancyGrid& rFrontiersMap,
74  std::vector<Vec2i>& rFrontiers,
75  std::vector<std::vector<Vec2i>>& rOutClusters);
76  Vec2i ClosestFrontierCluster(const Vec2i& rPos, std::vector<Vec2i>& rCluster);
77  Vec2i MedianFrontierCluster(const Vec2i& rPos, std::vector<Vec2i>& rCluster);
78  void ComputeCentroids(const Vec2i& rPos,
79  std::vector<std::vector<Vec2i>>& rClusters,
80  std::vector<Vec2i>& rOutCentroids);
81  void ComputeAverageCentroids(const Vec2i& rPos,
82  std::vector<std::vector<Vec2i>>& rClusters,
83  std::vector<Vec2i>& rOutCentroids);
84 };
85 #endif
sa::InitOccFrom
void InitOccFrom(nav_msgs::OccupancyGrid &rInput, nav_msgs::OccupancyGrid &rOutput)
Vec2i
Definition: Common.h:59
sa::ClosestFrontierCluster
Vec2i ClosestFrontierCluster(const Vec2i &rPos, std::vector< Vec2i > &rCluster)
sa::ComputePathWavefront
void ComputePathWavefront(nav_msgs::OccupancyGrid &rInput, const Vec2i &rStart, const Vec2i &rEnd, std::list< Vec2i > &rOutPath)
sa::MedianFrontierCluster
Vec2i MedianFrontierCluster(const Vec2i &rPos, std::vector< Vec2i > &rCluster)
sa::ComputePath
void ComputePath(nav_msgs::OccupancyGrid &rOcc, const Vec2i &rStart, const Vec2i &rEnd, std::list< Vec2i > &rOutPath)
sa::CheckAny
bool CheckAny(nav_msgs::OccupancyGrid &rInput, const Vec2i &rStart, const Vec2i &rEnd, const int &rVal)
sa
Definition: SearchAlgorithms.h:57
Common.h
sa::ComputeAverageCentroids
void ComputeAverageCentroids(const Vec2i &rPos, std::vector< std::vector< Vec2i >> &rClusters, std::vector< Vec2i > &rOutCentroids)
sa::IsInBounds
bool IsInBounds(nav_msgs::OccupancyGrid &rInput, Vec2i &rPos)
sa::ComputeClusters
void ComputeClusters(nav_msgs::OccupancyGrid &rFrontiersMap, std::vector< Vec2i > &rFrontiers, std::vector< std::vector< Vec2i >> &rOutClusters)
sa::ComputeCentroids
void ComputeCentroids(const Vec2i &rPos, std::vector< std::vector< Vec2i >> &rClusters, std::vector< Vec2i > &rOutCentroids)
sa::ComputeFrontiers
void ComputeFrontiers(nav_msgs::OccupancyGrid &rInput, nav_msgs::OccupancyGrid &rOutput, std::vector< Vec2i > &rFrontiers)