Coverage Control Library
Loading...
Searching...
No Matches
Core API

Core C++ API with python bindings. More...

Topics

 Constants
 
 Typedefs
 

Classes

class  Parameters
 Class to store parameters. More...
 
class  AbstractController
 
class  CentralizedCVT
 
class  ClairvoyantCVT
 
class  DecentralizedCVT
 
class  NearOptimalCVT
 
class  BivariateNormalDistribution
 Class for Bivariate Normal Distribution. More...
 
class  CoverageSystem
 The CoverageSystem class is the main class for the coverage control library. More...
 
class  RobotModel
 Class for handling the robot model. More...
 
class  Vec2d
 A class for 2D vector. More...
 
class  VoronoiCell
 Struct for Voronoi cell. More...
 
class  Voronoi
 Class for computing Voronoi cells. More...
 
class  WorldIDF
 Class for Importance Density Function (IDF) for the world. More...
 

Functions

auto NearOptimalCVTAlgorithm (int const num_tries, int const max_iterations, int const num_sites, MapType const &map, int const map_size, double const res)
 
auto NearOptimalCVTAlgorithm (int const num_tries, int const max_iterations, int const num_sites, MapType const &map, int const map_size, double const res, PointVector const &positions, Voronoi &voronoi)
 
auto NearOptimalCVTAlgorithm (int const num_tries, int const max_iterations, int const num_sites, MapType const &map, int const map_size, double const res, PointVector const &positions)
 

Detailed Description

Core C++ API with python bindings.

Function Documentation

◆ NearOptimalCVTAlgorithm() [1/3]

auto NearOptimalCVTAlgorithm ( int const num_tries,
int const max_iterations,
int const num_sites,
MapType const & map,
int const map_size,
double const res )
inline

Definition at line 59 of file near_optimal_cvt_algorithm.h.

◆ NearOptimalCVTAlgorithm() [2/3]

auto NearOptimalCVTAlgorithm ( int const num_tries,
int const max_iterations,
int const num_sites,
MapType const & map,
int const map_size,
double const res,
PointVector const & positions )
inline

Definition at line 150 of file near_optimal_cvt_algorithm.h.

◆ NearOptimalCVTAlgorithm() [3/3]

auto NearOptimalCVTAlgorithm ( int const num_tries,
int const max_iterations,
int const num_sites,
MapType const & map,
int const map_size,
double const res,
PointVector const & positions,
Voronoi & voronoi )
inline

Definition at line 119 of file near_optimal_cvt_algorithm.h.