#include <nav_msgs/OccupancyGrid.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <opencv2/core/utility.hpp>
#include <opencv2/imgcodecs.hpp>
#include <random>
Go to the source code of this file.
|
static bool | consistentData (const nav_msgs::OccupancyGrid &grid) |
|
static bool | isIdentity (const geometry_msgs::Transform &transform) |
|
static bool | isIdentity (const geometry_msgs::Quaternion &rotation) |
|
nav_msgs::OccupancyGridConstPtr | loadMap (const std::string &filename) |
|
template<typename InputIt > |
std::vector< nav_msgs::OccupancyGridConstPtr > | loadMaps (InputIt filenames_begin, InputIt filenames_end) |
|
static bool | operator== (const nav_msgs::OccupancyGrid &grid1, const nav_msgs::OccupancyGrid &grid2) |
|
std::tuple< double, double, double > | randomAngleTxTy () |
|
geometry_msgs::Transform | randomTransform () |
|
cv::Mat | randomTransformMatrix () |
|
void | saveMap (const std::string &filename, const nav_msgs::OccupancyGridConstPtr &map) |
|
◆ consistentData()
static bool consistentData |
( |
const nav_msgs::OccupancyGrid & |
grid | ) |
|
|
inlinestatic |
◆ isIdentity() [1/2]
static bool isIdentity |
( |
const geometry_msgs::Transform & |
transform | ) |
|
|
inlinestatic |
◆ isIdentity() [2/2]
static bool isIdentity |
( |
const geometry_msgs::Quaternion & |
rotation | ) |
|
|
inlinestatic |
◆ loadMap()
nav_msgs::OccupancyGridConstPtr loadMap |
( |
const std::string & |
filename | ) |
|
◆ loadMaps()
template<typename InputIt >
std::vector<nav_msgs::OccupancyGridConstPtr> loadMaps |
( |
InputIt |
filenames_begin, |
|
|
InputIt |
filenames_end |
|
) |
| |
◆ operator==()
static bool operator== |
( |
const nav_msgs::OccupancyGrid & |
grid1, |
|
|
const nav_msgs::OccupancyGrid & |
grid2 |
|
) |
| |
|
inlinestatic |
◆ randomAngleTxTy()
std::tuple< double, double, double > randomAngleTxTy |
( |
| ) |
|
◆ randomTransform()
geometry_msgs::Transform randomTransform |
( |
| ) |
|
◆ randomTransformMatrix()
cv::Mat randomTransformMatrix |
( |
| ) |
|
◆ saveMap()
void saveMap |
( |
const std::string & |
filename, |
|
|
const nav_msgs::OccupancyGridConstPtr & |
map |
|
) |
| |
◆ resolution
const float resolution = 0.05f |