Coverage Control Library
Loading...
Searching...
No Matches
clairvoyant_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_CLAIRVOYANT_CVT_H_
30#define CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_CLAIRVOYANT_CVT_H_
31
32#include <omp.h>
33
34#include <algorithm>
35#include <vector>
36
41
42namespace CoverageControl {
43
56 private:
57 Parameters const params_;
58 size_t num_robots_ = 0;
59 CoverageSystem &env_;
60 Voronoi voronoi_;
61 PointVector robot_global_positions_;
62 PointVector goals_, actions_;
63 std::vector<double> voronoi_mass_;
64
65 bool is_converged_ = false;
66
67 public:
69 : ClairvoyantCVT(params, params.pNumRobots, env) {}
70 ClairvoyantCVT(Parameters const &params, size_t const &num_robots,
71 CoverageSystem &env)
72 : params_{params}, num_robots_{num_robots}, env_{env} {
73 robot_global_positions_ = env_.GetRobotPositions();
74 actions_.resize(num_robots_);
75 goals_ = robot_global_positions_;
76 voronoi_mass_.resize(num_robots_, 0);
77 voronoi_ = Voronoi(robot_global_positions_, env_.GetWorldMap(),
78 Point2(params_.pWorldMapSize, params_.pWorldMapSize),
79 params_.pResolution);
81 }
82
83 PointVector GetActions() { return actions_; }
84
85 auto GetGoals() { return goals_; }
86
87 auto &GetVoronoi() { return voronoi_; }
88
89 void ComputeGoals() {
90 voronoi_ = Voronoi(robot_global_positions_, env_.GetWorldMap(),
91 Point2(params_.pWorldMapSize, params_.pWorldMapSize),
92 params_.pResolution);
93 auto voronoi_cells = voronoi_.GetVoronoiCells();
94 for (size_t iRobot = 0; iRobot < num_robots_; ++iRobot) {
95 goals_[iRobot] = voronoi_cells[iRobot].centroid();
96 voronoi_mass_[iRobot] = voronoi_cells[iRobot].mass();
97 }
98 }
99
101 is_converged_ = true;
102 robot_global_positions_ = env_.GetRobotPositions();
103 ComputeGoals();
104 auto voronoi_cells = voronoi_.GetVoronoiCells();
105 for (size_t iRobot = 0; iRobot < num_robots_; ++iRobot) {
106 actions_[iRobot] = Point2(0, 0);
107 Point2 diff = goals_[iRobot] - robot_global_positions_[iRobot];
108 double dist = diff.norm();
109 /* if (dist < 0.1 * params_.pResolution) { */
110 /* continue; */
111 /* } */
112 if (dist < kEps) {
113 continue;
114 }
115 if (env_.CheckOscillation(iRobot)) {
116 continue;
117 }
118 double speed = dist / params_.pTimeStep;
119 /* double speed = 2 * dist * voronoi_mass_[iRobot]; */
120 speed = std::min(params_.pMaxRobotSpeed, speed);
121 Point2 direction(diff);
122 direction.normalize();
123 actions_[iRobot] = speed * direction;
124 is_converged_ = false;
125 }
126 return 0;
127 }
128
129 bool IsConverged() const { return is_converged_; }
130};
131
132} // namespace CoverageControl
133#endif // CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_CLAIRVOYANT_CVT_H_
Contains the abstract class for coverage control algorithms.
ClairvoyantCVT(Parameters const &params, size_t const &num_robots, CoverageSystem &env)
ClairvoyantCVT(Parameters const &params, 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.
bool CheckOscillation(size_t const robot_id) const
const MapType & GetWorldMap() const
Get the world map.
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.