Coverage Control Library
Loading...
Searching...
No Matches
near_optimal_cvt_algorithm.h
Go to the documentation of this file.
1/*
2 * This file is part of the CoverageControl library
3 *
4 * Author: Saurav Agarwal
5 * Contact: sauravag@seas.upenn.edu, agr.saurav1@gmail.com
6 * Repository: https://github.com/KumarRobotics/CoverageControl
7 *
8 * Copyright (c) 2024, Saurav Agarwal
9 *
10 * The CoverageControl library is free software: you can redistribute it and/or
11 * modify it under the terms of the GNU General Public License as published by
12 * the Free Software Foundation, either version 3 of the License, or (at your
13 * option) any later version.
14 *
15 * The CoverageControl library is distributed in the hope that it will be
16 * useful, but WITHOUT ANY WARRANTY; without even the implied warranty of
17 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
18 * Public License for more details.
19 *
20 * You should have received a copy of the GNU General Public License along with
21 * CoverageControl library. If not, see <https://www.gnu.org/licenses/>.
22 */
23
35#ifndef CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_NEAR_OPTIMAL_CVT_ALGORITHM_H_
36#define CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_NEAR_OPTIMAL_CVT_ALGORITHM_H_
37
38#define EIGEN_NO_CUDA // Don't use eigen's cuda facility
39#include <omp.h>
40#include <time.h>
41
42#include <Eigen/Dense> // Eigen is used for maps
43#include <fstream>
44#include <iostream>
45#include <random>
46#include <vector>
47
48#include "CoverageControl/extern/lsap/Hungarian.h"
51
52namespace CoverageControl {
53
59inline auto NearOptimalCVTAlgorithm(int const num_tries,
60 int const max_iterations,
61 int const num_sites, MapType const &map,
62 int const map_size, double const res) {
63 std::random_device
64 rd_; // Will be used to obtain a seed for the random number engine
65 std::mt19937 gen_;
66 std::srand(time(NULL));
67 gen_ = std::mt19937(
68 rd_()); // Standard mersenne_twister_engine seeded with rd_()
69 std::vector<Voronoi> all_voronoi_cells;
70 /* all_voronoi_cells.resize(num_tries, std::vector<VoronoiCell>(num_sites));
71 */
72 all_voronoi_cells.resize(num_tries);
73 std::vector<double> obj_values;
74 obj_values.resize(num_tries, 0);
75 std::uniform_real_distribution<> distrib_pts(0.001, map_size * res - 0.001);
76
77#pragma omp parallel for
78 for (int iter = 0; iter < num_tries; ++iter) {
79 PointVector sites;
80 sites.resize(num_sites);
81 for (int iSite = 0; iSite < num_sites; ++iSite) {
82 sites[iSite] = Point2(distrib_pts(gen_), distrib_pts(gen_));
83 }
84 bool cont_flag = true;
85 /* std::cout << "voronoi start" << std::endl; */
86 Voronoi voronoi(sites, map, Point2(map_size, map_size), res);
87 /* std::cout << "voronoi end" << std::endl; */
88 auto voronoi_cells = voronoi.GetVoronoiCells();
89 int iSteps = 0;
90 for (iSteps = 0; iSteps < max_iterations and cont_flag == true; ++iSteps) {
91 cont_flag = false;
92 voronoi_cells = voronoi.GetVoronoiCells();
93 for (int iSite = 0; iSite < num_sites; ++iSite) {
94 Point2 diff =
95 voronoi_cells[iSite].centroid() - voronoi_cells[iSite].site;
96 if (diff.norm() < res) {
97 continue;
98 }
99 cont_flag = true;
100 sites[iSite] = voronoi_cells[iSite].centroid();
101 }
102 voronoi.UpdateSites(sites);
103 }
104 /* std::cout << "No. of voronoi steps: " << iSteps << std::endl; */
105 all_voronoi_cells[iter] = voronoi;
106 obj_values[iter] = voronoi.GetSumIDFGoalDistSqr();
107 }
108 int best_vornoi_idx = 0;
109 double min = obj_values[0];
110 for (int iter = 1; iter < num_tries; ++iter) {
111 if (obj_values[iter] < min) {
112 min = obj_values[iter];
113 best_vornoi_idx = iter;
114 }
115 }
116 return all_voronoi_cells[best_vornoi_idx];
117}
118
119inline auto NearOptimalCVTAlgorithm(int const num_tries,
120 int const max_iterations,
121 int const num_sites, MapType const &map,
122 int const map_size, double const res,
123 PointVector const &positions,
124 Voronoi &voronoi) {
125 voronoi = NearOptimalCVTAlgorithm(num_tries, max_iterations, num_sites, map,
126 map_size, res);
127 auto voronoi_cells = voronoi.GetVoronoiCells();
128 std::vector<std::vector<double>> cost_matrix;
129 cost_matrix.resize(num_sites, std::vector<double>(num_sites));
130#pragma omp parallel for num_threads(num_sites)
131 for (int iRobot = 0; iRobot < num_sites; ++iRobot) {
132 for (int jCentroid = 0; jCentroid < num_sites; ++jCentroid) {
133 cost_matrix[iRobot][jCentroid] =
134 (positions[iRobot] - voronoi_cells[jCentroid].centroid()).norm();
135 }
136 }
137 HungarianAlgorithm HungAlgo;
138 std::vector<int> assignment;
139 HungAlgo.Solve(cost_matrix, assignment);
140
141 PointVector goals;
142 goals.resize(num_sites);
143 for (int iRobot = 0; iRobot < num_sites; ++iRobot) {
144 goals[iRobot] = voronoi_cells[assignment[iRobot]].centroid();
145 }
146
147 return goals;
148}
149
150inline auto NearOptimalCVTAlgorithm(int const num_tries,
151 int const max_iterations,
152 int const num_sites, MapType const &map,
153 int const map_size, double const res,
154 PointVector const &positions) {
155 Voronoi voronoi;
156 return NearOptimalCVTAlgorithm(num_tries, max_iterations, num_sites, map,
157 map_size, res, positions, voronoi);
158}
159
163} /* namespace CoverageControl */
164#endif // CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_NEAR_OPTIMAL_CVT_ALGORITHM_H_
Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > MapType
Definition typedefs.h:48
Eigen::Vector2d Point2
Definition typedefs.h:44
Namespace for the CoverageControl library.
Contains parameters.
Contains typedefs for the library.