Public Member Functions | Private Attributes | List of all members
rtabmap_util::MapsManager Class Reference

#include <MapsManager.h>

Public Member Functions

void backwardCompatibilityParameters (ros::NodeHandle &pnh, rtabmap::ParametersMap &parameters) const
 
void clear ()
 
std::map< int, rtabmap::TransformgetFilteredPoses (const std::map< int, rtabmap::Transform > &poses)
 
cv::Mat getGridMap (float &xMin, float &yMin, float &gridCellSize)
 
cv::Mat getGridProbMap (float &xMin, float &yMin, float &gridCellSize)
 
const rtabmap::LocalGridMakergetLocalMapMaker () const
 
const rtabmap::OccupancyGridgetOccupancyGrid () const
 
const rtabmap::OctoMapgetOctomap () const
 
bool hasSubscribers () const
 
void init (ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name, bool usePublicNamespace)
 
bool isLatching () const
 
bool isMapUpdated () const
 
 MapsManager ()
 
void publishMaps (const std::map< int, rtabmap::Transform > &poses, const ros::Time &stamp, const std::string &mapFrameId)
 
void set2DMap (const cv::Mat &map, float xMin, float yMin, float cellSize, const std::map< int, rtabmap::Transform > &poses, const rtabmap::Memory *memory=0)
 
void setParameters (const rtabmap::ParametersMap &parameters)
 
std::map< int, rtabmap::TransformupdateMapCaches (const std::map< int, rtabmap::Transform > &poses, const rtabmap::Memory *memory, bool updateGrid, bool updateOctomap, const std::map< int, rtabmap::Signature > &signatures=std::map< int, rtabmap::Signature >())
 
virtual ~MapsManager ()
 

Private Attributes

bool alwaysUpdateMap_
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledGround_
 
rtabmap::FlannIndex assembledGroundIndex_
 
std::map< int, rtabmap::TransformassembledGroundPoses_
 
rtabmap::FlannIndex assembledObstacleIndex_
 
std::map< int, rtabmap::TransformassembledObstaclePoses_
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledObstacles_
 
ros::Publisher cloudGroundPub_
 
ros::Publisher cloudMapPub_
 
ros::Publisher cloudObstaclesPub_
 
bool cloudOutputVoxelized_
 
bool cloudSubtractFiltering_
 
int cloudSubtractFilteringMinNeighbors_
 
rtabmap::GridMapelevationMap_
 
ros::Publisher elevationMapPub_
 
bool elevationMapUpdated_
 
ros::Publisher gridMapPub_
 
ros::Publisher gridProbMapPub_
 
bool gridUpdated_
 
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > groundClouds_
 
std::map< void *, bool > latched_
 
bool latching_
 
rtabmap::LocalGridMakerlocalMapMaker_
 
rtabmap::LocalGridCache localMaps_
 
bool mapCacheCleanup_
 
double mapFilterAngle_
 
double mapFilterRadius_
 
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > obstacleClouds_
 
rtabmap::OccupancyGridoccupancyGrid_
 
rtabmap::OctoMapoctomap_
 
ros::Publisher octoMapCloud_
 
ros::Publisher octoMapEmptySpace_
 
ros::Publisher octoMapFrontierCloud_
 
ros::Publisher octoMapGroundCloud_
 
ros::Publisher octoMapObstacleCloud_
 
ros::Publisher octoMapProj_
 
ros::Publisher octoMapPubBin_
 
ros::Publisher octoMapPubFull_
 
int octomapTreeDepth_
 
bool octomapUpdated_
 
rtabmap::ParametersMap parameters_
 
ros::Publisher projMapPub_
 
bool scanEmptyRayTracing_
 
ros::Publisher scanMapPub_
 

Detailed Description

Definition at line 51 of file MapsManager.h.

Constructor & Destructor Documentation

◆ MapsManager()

rtabmap_util::MapsManager::MapsManager ( )

Definition at line 64 of file MapsManager.cpp.

◆ ~MapsManager()

rtabmap_util::MapsManager::~MapsManager ( )
virtual

Definition at line 221 of file MapsManager.cpp.

Member Function Documentation

◆ backwardCompatibilityParameters()

void rtabmap_util::MapsManager::backwardCompatibilityParameters ( ros::NodeHandle pnh,
rtabmap::ParametersMap parameters 
) const

Definition at line 289 of file MapsManager.cpp.

◆ clear()

void rtabmap_util::MapsManager::clear ( )

Definition at line 390 of file MapsManager.cpp.

◆ getFilteredPoses()

std::map< int, Transform > rtabmap_util::MapsManager::getFilteredPoses ( const std::map< int, rtabmap::Transform > &  poses)

Definition at line 446 of file MapsManager.cpp.

◆ getGridMap()

cv::Mat rtabmap_util::MapsManager::getGridMap ( float xMin,
float yMin,
float gridCellSize 
)

Definition at line 1518 of file MapsManager.cpp.

◆ getGridProbMap()

cv::Mat rtabmap_util::MapsManager::getGridProbMap ( float xMin,
float yMin,
float gridCellSize 
)

Definition at line 1527 of file MapsManager.cpp.

◆ getLocalMapMaker()

const rtabmap::LocalGridMaker* rtabmap_util::MapsManager::getLocalMapMaker ( ) const
inline

Definition at line 91 of file MapsManager.h.

◆ getOccupancyGrid()

const rtabmap::OccupancyGrid* rtabmap_util::MapsManager::getOccupancyGrid ( ) const
inline

Definition at line 90 of file MapsManager.h.

◆ getOctomap()

const rtabmap::OctoMap* rtabmap_util::MapsManager::getOctomap ( ) const
inline

Definition at line 89 of file MapsManager.h.

◆ hasSubscribers()

bool rtabmap_util::MapsManager::hasSubscribers ( ) const

Definition at line 414 of file MapsManager.cpp.

◆ init()

void rtabmap_util::MapsManager::init ( ros::NodeHandle nh,
ros::NodeHandle pnh,
const std::string name,
bool  usePublicNamespace 
)

Definition at line 95 of file MapsManager.cpp.

◆ isLatching()

bool rtabmap_util::MapsManager::isLatching ( ) const
inline

Definition at line 58 of file MapsManager.h.

◆ isMapUpdated()

bool rtabmap_util::MapsManager::isMapUpdated ( ) const

Definition at line 434 of file MapsManager.cpp.

◆ publishMaps()

void rtabmap_util::MapsManager::publishMaps ( const std::map< int, rtabmap::Transform > &  poses,
const ros::Time stamp,
const std::string mapFrameId 
)

Definition at line 777 of file MapsManager.cpp.

◆ set2DMap()

void rtabmap_util::MapsManager::set2DMap ( const cv::Mat map,
float  xMin,
float  yMin,
float  cellSize,
const std::map< int, rtabmap::Transform > &  poses,
const rtabmap::Memory memory = 0 
)

Definition at line 348 of file MapsManager.cpp.

◆ setParameters()

void rtabmap_util::MapsManager::setParameters ( const rtabmap::ParametersMap parameters)

Definition at line 329 of file MapsManager.cpp.

◆ updateMapCaches()

std::map< int, rtabmap::Transform > rtabmap_util::MapsManager::updateMapCaches ( const std::map< int, rtabmap::Transform > &  poses,
const rtabmap::Memory memory,
bool  updateGrid,
bool  updateOctomap,
const std::map< int, rtabmap::Signature > &  signatures = std::map<intrtabmap::Signature>() 
)

Definition at line 457 of file MapsManager.cpp.

Member Data Documentation

◆ alwaysUpdateMap_

bool rtabmap_util::MapsManager::alwaysUpdateMap_
private

Definition at line 101 of file MapsManager.h.

◆ assembledGround_

pcl::PointCloud<pcl::PointXYZRGB>::Ptr rtabmap_util::MapsManager::assembledGround_
private

Definition at line 124 of file MapsManager.h.

◆ assembledGroundIndex_

rtabmap::FlannIndex rtabmap_util::MapsManager::assembledGroundIndex_
private

Definition at line 125 of file MapsManager.h.

◆ assembledGroundPoses_

std::map<int, rtabmap::Transform> rtabmap_util::MapsManager::assembledGroundPoses_
private

Definition at line 121 of file MapsManager.h.

◆ assembledObstacleIndex_

rtabmap::FlannIndex rtabmap_util::MapsManager::assembledObstacleIndex_
private

Definition at line 126 of file MapsManager.h.

◆ assembledObstaclePoses_

std::map<int, rtabmap::Transform> rtabmap_util::MapsManager::assembledObstaclePoses_
private

Definition at line 122 of file MapsManager.h.

◆ assembledObstacles_

pcl::PointCloud<pcl::PointXYZRGB>::Ptr rtabmap_util::MapsManager::assembledObstacles_
private

Definition at line 123 of file MapsManager.h.

◆ cloudGroundPub_

ros::Publisher rtabmap_util::MapsManager::cloudGroundPub_
private

Definition at line 105 of file MapsManager.h.

◆ cloudMapPub_

ros::Publisher rtabmap_util::MapsManager::cloudMapPub_
private

Definition at line 104 of file MapsManager.h.

◆ cloudObstaclesPub_

ros::Publisher rtabmap_util::MapsManager::cloudObstaclesPub_
private

Definition at line 106 of file MapsManager.h.

◆ cloudOutputVoxelized_

bool rtabmap_util::MapsManager::cloudOutputVoxelized_
private

Definition at line 95 of file MapsManager.h.

◆ cloudSubtractFiltering_

bool rtabmap_util::MapsManager::cloudSubtractFiltering_
private

Definition at line 96 of file MapsManager.h.

◆ cloudSubtractFilteringMinNeighbors_

int rtabmap_util::MapsManager::cloudSubtractFilteringMinNeighbors_
private

Definition at line 97 of file MapsManager.h.

◆ elevationMap_

rtabmap::GridMap* rtabmap_util::MapsManager::elevationMap_
private

Definition at line 140 of file MapsManager.h.

◆ elevationMapPub_

ros::Publisher rtabmap_util::MapsManager::elevationMapPub_
private

Definition at line 119 of file MapsManager.h.

◆ elevationMapUpdated_

bool rtabmap_util::MapsManager::elevationMapUpdated_
private

Definition at line 141 of file MapsManager.h.

◆ gridMapPub_

ros::Publisher rtabmap_util::MapsManager::gridMapPub_
private

Definition at line 108 of file MapsManager.h.

◆ gridProbMapPub_

ros::Publisher rtabmap_util::MapsManager::gridProbMapPub_
private

Definition at line 109 of file MapsManager.h.

◆ gridUpdated_

bool rtabmap_util::MapsManager::gridUpdated_
private

Definition at line 134 of file MapsManager.h.

◆ groundClouds_

std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > rtabmap_util::MapsManager::groundClouds_
private

Definition at line 127 of file MapsManager.h.

◆ latched_

std::map<void*, bool> rtabmap_util::MapsManager::latched_
private

Definition at line 146 of file MapsManager.h.

◆ latching_

bool rtabmap_util::MapsManager::latching_
private

Definition at line 145 of file MapsManager.h.

◆ localMapMaker_

rtabmap::LocalGridMaker* rtabmap_util::MapsManager::localMapMaker_
private

Definition at line 133 of file MapsManager.h.

◆ localMaps_

rtabmap::LocalGridCache rtabmap_util::MapsManager::localMaps_
private

Definition at line 130 of file MapsManager.h.

◆ mapCacheCleanup_

bool rtabmap_util::MapsManager::mapCacheCleanup_
private

Definition at line 100 of file MapsManager.h.

◆ mapFilterAngle_

double rtabmap_util::MapsManager::mapFilterAngle_
private

Definition at line 99 of file MapsManager.h.

◆ mapFilterRadius_

double rtabmap_util::MapsManager::mapFilterRadius_
private

Definition at line 98 of file MapsManager.h.

◆ obstacleClouds_

std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > rtabmap_util::MapsManager::obstacleClouds_
private

Definition at line 128 of file MapsManager.h.

◆ occupancyGrid_

rtabmap::OccupancyGrid* rtabmap_util::MapsManager::occupancyGrid_
private

Definition at line 132 of file MapsManager.h.

◆ octomap_

rtabmap::OctoMap* rtabmap_util::MapsManager::octomap_
private

Definition at line 136 of file MapsManager.h.

◆ octoMapCloud_

ros::Publisher rtabmap_util::MapsManager::octoMapCloud_
private

Definition at line 113 of file MapsManager.h.

◆ octoMapEmptySpace_

ros::Publisher rtabmap_util::MapsManager::octoMapEmptySpace_
private

Definition at line 117 of file MapsManager.h.

◆ octoMapFrontierCloud_

ros::Publisher rtabmap_util::MapsManager::octoMapFrontierCloud_
private

Definition at line 114 of file MapsManager.h.

◆ octoMapGroundCloud_

ros::Publisher rtabmap_util::MapsManager::octoMapGroundCloud_
private

Definition at line 115 of file MapsManager.h.

◆ octoMapObstacleCloud_

ros::Publisher rtabmap_util::MapsManager::octoMapObstacleCloud_
private

Definition at line 116 of file MapsManager.h.

◆ octoMapProj_

ros::Publisher rtabmap_util::MapsManager::octoMapProj_
private

Definition at line 118 of file MapsManager.h.

◆ octoMapPubBin_

ros::Publisher rtabmap_util::MapsManager::octoMapPubBin_
private

Definition at line 111 of file MapsManager.h.

◆ octoMapPubFull_

ros::Publisher rtabmap_util::MapsManager::octoMapPubFull_
private

Definition at line 112 of file MapsManager.h.

◆ octomapTreeDepth_

int rtabmap_util::MapsManager::octomapTreeDepth_
private

Definition at line 137 of file MapsManager.h.

◆ octomapUpdated_

bool rtabmap_util::MapsManager::octomapUpdated_
private

Definition at line 138 of file MapsManager.h.

◆ parameters_

rtabmap::ParametersMap rtabmap_util::MapsManager::parameters_
private

Definition at line 143 of file MapsManager.h.

◆ projMapPub_

ros::Publisher rtabmap_util::MapsManager::projMapPub_
private

Definition at line 107 of file MapsManager.h.

◆ scanEmptyRayTracing_

bool rtabmap_util::MapsManager::scanEmptyRayTracing_
private

Definition at line 102 of file MapsManager.h.

◆ scanMapPub_

ros::Publisher rtabmap_util::MapsManager::scanMapPub_
private

Definition at line 110 of file MapsManager.h.


The documentation for this class was generated from the following files:


rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50