33#ifndef CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_NEAR_OPTIMAL_CVT_H_
34#define CPPSRC_CORE_INCLUDE_COVERAGECONTROL_ALGORITHMS_NEAR_OPTIMAL_CVT_H_
63 size_t num_robots_ = 0;
69 bool is_converged_ =
false;
76 : params_{params}, num_robots_{num_robots}, env_{env} {
78 actions_.resize(num_robots_);
79 goals_ = robot_global_positions_;
93 robot_global_positions_, voronoi_);
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();
109 direction.normalize();
110 actions_[iRobot] = speed * direction;
111 is_converged_ =
false;
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 ¶ms, CoverageSystem &env)
NearOptimalCVT(Parameters const ¶ms, size_t const &num_robots, CoverageSystem &env)
Class to store parameters.
double pTimeStep
Each time step corresponds to pTimeStep seconds.
Class for computing Voronoi cells.
The file contains the CoverageSystem class, which is the main class for the coverage control library.
std::vector< Point2 > PointVector
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 typedefs for the library.