Coverage Control Library
Loading...
Searching...
No Matches
near_optimal_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
33#ifndef CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_NEAR_OPTIMAL_CVT_H_
34#define CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_NEAR_OPTIMAL_CVT_H_
35
36#include <omp.h>
37
38#include <algorithm>
39#include <vector>
40
46
47namespace CoverageControl {
48
61 private:
62 Parameters const params_;
63 size_t num_robots_ = 0;
64 CoverageSystem &env_;
65 Voronoi voronoi_;
66 PointVector robot_global_positions_;
67 PointVector goals_, actions_;
68
69 bool is_converged_ = false;
70
71 public:
73 : NearOptimalCVT(params, params.pNumRobots, env) {}
74 NearOptimalCVT(Parameters const &params, size_t const &num_robots,
75 CoverageSystem &env)
76 : params_{params}, num_robots_{num_robots}, env_{env} {
77 robot_global_positions_ = env_.GetRobotPositions();
78 actions_.resize(num_robots_);
79 goals_ = robot_global_positions_;
81 }
82
83 PointVector GetActions() { return actions_; }
84
85 auto GetGoals() { return goals_; }
86
87 auto &GetVoronoi() { return voronoi_; }
88
89 void ComputeGoals() {
91 params_.pLloydNumTries, params_.pLloydMaxIterations, num_robots_,
92 env_.GetWorldMap(), params_.pWorldMapSize, params_.pResolution,
93 robot_global_positions_, voronoi_);
94 }
95
97 is_converged_ = true;
98 robot_global_positions_ = env_.GetRobotPositions();
99 for (size_t iRobot = 0; iRobot < num_robots_; ++iRobot) {
100 actions_[iRobot] = Point2(0, 0);
101 Point2 diff = goals_[iRobot] - robot_global_positions_[iRobot];
102 double dist = diff.norm();
103 if (dist < kEps) {
104 continue;
105 }
106 double speed = dist / params_.pTimeStep;
107 speed = std::min(params_.pMaxRobotSpeed, speed);
108 Point2 direction(diff);
109 direction.normalize();
110 actions_[iRobot] = speed * direction;
111 is_converged_ = false;
112 }
113 return 0;
114 }
115
116 bool IsConverged() { return is_converged_; }
117};
118
119} /* namespace CoverageControl */
120#endif // CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_NEAR_OPTIMAL_CVT_H_
Contains the abstract class for coverage control algorithms.
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 & GetWorldMap() const
Get the world map.
NearOptimalCVT(Parameters const &params, CoverageSystem &env)
NearOptimalCVT(Parameters const &params, size_t const &num_robots, CoverageSystem &env)
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
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
auto NearOptimalCVTAlgorithm(int const num_tries, int const max_iterations, int const num_sites, MapType const &map, int const map_size, double const res)
Namespace for the CoverageControl library.
Near Optimal Centroidal Voronoi Tessellation (CVT) algorithm Near-optimal Centroidal Voronoi Tessella...
Contains parameters.
Contains typedefs for the library.