Go to the documentation of this file.
28 #ifndef MAPSMANAGER_H_
29 #define MAPSMANAGER_H_
35 #include <pcl/point_cloud.h>
36 #include <pcl/point_types.h>
38 #include <ros/publisher.h>
62 void set2DMap(
const cv::Mat & map,
float xMin,
float yMin,
float cellSize,
const std::map<int, rtabmap::Transform> & poses,
const rtabmap::Memory * memory = 0);
65 const std::map<int, rtabmap::Transform> & poses);
68 const std::map<int, rtabmap::Transform> & poses,
72 const std::map<int, rtabmap::Signature> & signatures = std::map<int, rtabmap::Signature>());
75 const std::map<int, rtabmap::Transform> & poses,
77 const std::string & mapFrameId);
82 float & gridCellSize);
87 float & gridCellSize);
rtabmap::ParametersMap parameters_
ros::Publisher octoMapGroundCloud_
cv::Mat getGridProbMap(float &xMin, float &yMin, float &gridCellSize)
rtabmap::LocalGridMaker * localMapMaker_
ros::Publisher cloudObstaclesPub_
ros::Publisher octoMapEmptySpace_
bool isMapUpdated() const
std::map< int, rtabmap::Transform > assembledGroundPoses_
const rtabmap::OctoMap * getOctomap() const
ros::Publisher cloudMapPub_
ros::Publisher cloudGroundPub_
ros::Publisher scanMapPub_
std::map< std::string, std::string > ParametersMap
rtabmap::OccupancyGrid * occupancyGrid_
ros::Publisher octoMapCloud_
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > groundClouds_
rtabmap::OctoMap * octomap_
int cloudSubtractFilteringMinNeighbors_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledObstacles_
ros::Publisher octoMapPubBin_
rtabmap::LocalGridCache localMaps_
std::map< int, rtabmap::Transform > getFilteredPoses(const std::map< int, rtabmap::Transform > &poses)
ros::Publisher elevationMapPub_
ros::Publisher gridProbMapPub_
ros::Publisher octoMapProj_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledGround_
void set2DMap(const cv::Mat &map, float xMin, float yMin, float cellSize, const std::map< int, rtabmap::Transform > &poses, const rtabmap::Memory *memory=0)
bool scanEmptyRayTracing_
cv::Mat getGridMap(float &xMin, float &yMin, float &gridCellSize)
std::map< int, rtabmap::Transform > assembledObstaclePoses_
rtabmap::GridMap * elevationMap_
rtabmap::FlannIndex assembledGroundIndex_
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > obstacleClouds_
bool hasSubscribers() const
const rtabmap::OccupancyGrid * getOccupancyGrid() const
void init(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name, bool usePublicNamespace)
ros::Publisher octoMapObstacleCloud_
bool cloudOutputVoxelized_
bool elevationMapUpdated_
std::map< void *, bool > latched_
rtabmap::FlannIndex assembledObstacleIndex_
const rtabmap::LocalGridMaker * getLocalMapMaker() const
ros::Publisher projMapPub_
bool cloudSubtractFiltering_
void setParameters(const rtabmap::ParametersMap ¶meters)
std::map< int, rtabmap::Transform > 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< int, rtabmap::Signature >())
ros::Publisher octoMapPubFull_
void backwardCompatibilityParameters(ros::NodeHandle &pnh, rtabmap::ParametersMap ¶meters) const
void publishMaps(const std::map< int, rtabmap::Transform > &poses, const ros::Time &stamp, const std::string &mapFrameId)
ros::Publisher gridMapPub_
ros::Publisher octoMapFrontierCloud_
rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50