Coverage Control Library
Loading...
Searching...
No Matches
centralized_cvt.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
29#ifndef CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_CENTRALIZED_CVT_H_
30#define CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_CENTRALIZED_CVT_H_
31
32#include <omp.h>
33
34#include <algorithm>
35#include <vector>
36
41
42namespace CoverageControl {
43
57 private:
58 Parameters const params_;
59 size_t num_robots_ = 0;
60 CoverageSystem &env_;
61 Voronoi voronoi_;
62 PointVector robot_global_positions_;
63 PointVector goals_, actions_;
64 std::vector<double> voronoi_mass_;
65
66 bool is_converged_ = false;
67
68 public:
70 : CentralizedCVT(params, params.pNumRobots, env) {}
71 CentralizedCVT(Parameters const &params, size_t const &num_robots,
72 CoverageSystem &env)
73 : params_{params}, num_robots_{num_robots}, env_{env} {
74 robot_global_positions_ = env_.GetRobotPositions();
75 actions_.resize(num_robots_);
76 goals_ = robot_global_positions_;
77 voronoi_mass_.resize(num_robots_, 0);
78 voronoi_ = Voronoi(robot_global_positions_, env_.GetSystemExploredIDFMap(),
79 Point2(params_.pWorldMapSize, params_.pWorldMapSize),
80 params_.pResolution);
82 }
83
84 PointVector GetActions() { return actions_; }
85
86 auto GetGoals() { return goals_; }
87
88 auto &GetVoronoi() { return voronoi_; }
89
90 void ComputeGoals() {
91 voronoi_ = Voronoi(robot_global_positions_, env_.GetSystemExploredIDFMap(),
92 Point2(params_.pWorldMapSize, params_.pWorldMapSize),
93 params_.pResolution);
94 auto voronoi_cells = voronoi_.GetVoronoiCells();
95 for (size_t iRobot = 0; iRobot < num_robots_; ++iRobot) {
96 goals_[iRobot] = voronoi_cells[iRobot].centroid();
97 voronoi_mass_[iRobot] = voronoi_cells[iRobot].mass();
98 }
99 }
100
101 bool IsConverged() const { return is_converged_; }
102
104 is_converged_ = true;
105 robot_global_positions_ = env_.GetRobotPositions();
106 ComputeGoals();
107 auto voronoi_cells = voronoi_.GetVoronoiCells();
108 for (size_t iRobot = 0; iRobot < num_robots_; ++iRobot) {
109 actions_[iRobot] = Point2(0, 0);
110 Point2 diff = goals_[iRobot] - robot_global_positions_[iRobot];
111 double dist = diff.norm();
112 /* if (dist < 0.1 * params_.pResolution) { */
113 /* continue; */
114 /* } */
115 if (dist < kEps) {
116 continue;
117 }
118 if (env_.CheckOscillation(iRobot)) {
119 continue;
120 }
121 double speed = dist / params_.pTimeStep;
122 /* double speed = 2 * dist * voronoi_mass_[iRobot]; */
123 speed = std::min(params_.pMaxRobotSpeed, speed);
124 Point2 direction(diff);
125 direction.normalize();
126 actions_[iRobot] = speed * direction;
127 is_converged_ = false;
128 }
129 return 0;
130 }
131};
132
133} /* namespace CoverageControl */
134#endif // CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_CENTRALIZED_CVT_H_
Contains the abstract class for coverage control algorithms.
CentralizedCVT(Parameters const &params, CoverageSystem &env)
CentralizedCVT(Parameters const &params, size_t const &num_robots, CoverageSystem &env)
The CoverageSystem class is the main class for the coverage control library.
PointVector GetRobotPositions(bool force_no_noise=false)
Get the global positions of all robots.
const MapType & GetSystemExploredIDFMap() const
bool CheckOscillation(size_t const robot_id) const
Class to store parameters.
Definition parameters.h:48
double pTimeStep
Each time step corresponds to pTimeStep seconds.
Definition parameters.h:140
Class for computing Voronoi cells.
Definition voronoi.h:116
auto GetVoronoiCells() const
Definition voronoi.h:185
The file contains the CoverageSystem class, which is the main class for the coverage control library.
double const kEps
Definition constants.h:48
std::vector< Point2 > PointVector
Definition typedefs.h:51
Eigen::Vector2d Point2
Definition typedefs.h:44
Namespace for the CoverageControl library.
Contains parameters.
Contains typedefs for the library.