Go to the documentation of this file.
   30 #ifndef OCTOMAP_SERVER_OCTOMAPSERVER_H 
   31 #define OCTOMAP_SERVER_OCTOMAPSERVER_H 
   34 #include <visualization_msgs/MarkerArray.h> 
   35 #include <nav_msgs/OccupancyGrid.h> 
   36 #include <std_msgs/ColorRGBA.h> 
   40 #include <sensor_msgs/PointCloud2.h> 
   41 #include <std_srvs/Empty.h> 
   42 #include <dynamic_reconfigure/server.h> 
   43 #include <octomap_server/OctomapServerConfig.h> 
   45 #include <pcl/point_types.h> 
   46 #include <pcl/conversions.h> 
   48 #include <pcl/sample_consensus/method_types.h> 
   50 #pragma GCC diagnostic push 
   51 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"  // pcl::SAC_SAMPLE_SIZE is protected since PCL 1.8.0 
   52 #include <pcl/sample_consensus/model_types.h> 
   53 #pragma GCC diagnostic pop 
   55 #include <pcl/segmentation/sac_segmentation.h> 
   56 #include <pcl/io/pcd_io.h> 
   57 #include <pcl/filters/extract_indices.h> 
   58 #include <pcl/filters/passthrough.h> 
   65 #include <octomap_msgs/Octomap.h> 
   66 #include <octomap_msgs/GetOctomap.h> 
   67 #include <octomap_msgs/BoundingBoxQuery.h> 
   76 #ifdef COLOR_OCTOMAP_SERVER 
   84 #ifdef COLOR_OCTOMAP_SERVER 
   94   typedef octomap_msgs::BoundingBoxQuery 
BBXSrv;
 
   98   virtual bool octomapBinarySrv(OctomapSrv::Request  &req, OctomapSrv::GetOctomap::Response &res);
 
   99   virtual bool octomapFullSrv(OctomapSrv::Request  &req, OctomapSrv::GetOctomap::Response &res);
 
  100   bool clearBBXSrv(BBXSrv::Request& req, BBXSrv::Response& resp);
 
  101   bool resetSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp);
 
  104   virtual bool openFile(
const std::string& filename);
 
  108     for (
unsigned i = 0; i < 3; ++i)
 
  109       min[i] = std::min(in[i], min[i]);
 
  113     for (
unsigned i = 0; i < 3; ++i)
 
  181   inline unsigned mapIdx(
int i, 
int j)
 const {
 
  197   void adjustMapData(nav_msgs::OccupancyGrid& map, 
const nav_msgs::MapMetaData& oldMapInfo) 
const;
 
  199   inline bool mapChanged(
const nav_msgs::MapMetaData& oldMapInfo, 
const nav_msgs::MapMetaData& newMapInfo) {
 
  200     return (    oldMapInfo.height != newMapInfo.height
 
  201                 || oldMapInfo.width != newMapInfo.width
 
  202                 || oldMapInfo.origin.position.x != newMapInfo.origin.position.x
 
  203                 || oldMapInfo.origin.position.y != newMapInfo.origin.position.y);
 
  
ros::ServiceServer m_resetService
virtual bool octomapBinarySrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res)
OctomapServer(const ros::NodeHandle private_nh_=ros::NodeHandle("~"), const ros::NodeHandle &nh_=ros::NodeHandle())
dynamic_reconfigure::Server< OctomapServerConfig > m_reconfigureServer
void filterGroundPlane(const PCLPointCloud &pc, PCLPointCloud &ground, PCLPointCloud &nonground) const
label the input cloud "pc" into ground and nonground. Should be in the robot's fixed frame (not world...
virtual void handleNode(const OcTreeT::iterator &it)
hook that is called when traversing all nodes of the updated Octree (does nothing here)
std::string m_baseFrameId
static void updateMaxKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &max)
octomap_msgs::GetOctomap OctomapSrv
pcl::PointCloud< pcl::PointXYZ > PCLPointCloud
virtual void insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud)
virtual bool openFile(const std::string &filename)
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_tfPointCloudSub
static std_msgs::ColorRGBA heightMapColor(double h)
bool isSpeckleNode(const octomap::OcTreeKey &key) const
Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution!
bool resetSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
octomap::OcTreeKey m_paddedMinKey
virtual void handlePreNodeTraversal(const ros::Time &rostime)
hook that is called before traversing all nodes
ros::Publisher m_collisionObjectPub
virtual bool octomapFullSrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res)
unsigned m_multires2DScale
virtual void publishAll(const ros::Time &rostime=ros::Time::now())
ros::NodeHandle m_nh_private
void publishBinaryOctoMap(const ros::Time &rostime=ros::Time::now()) const
virtual void handleFreeNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing free nodes in the updated area (updates 2D map projection here)
void publishProjected2DMap(const ros::Time &rostime=ros::Time::now())
double m_groundFilterAngle
ros::ServiceServer m_octomapFullService
bool mapChanged(const nav_msgs::MapMetaData &oldMapInfo, const nav_msgs::MapMetaData &newMapInfo)
ros::ServiceServer m_octomapBinaryService
bool clearBBXSrv(BBXSrv::Request &req, BBXSrv::Response &resp)
static void updateMinKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &min)
ros::Publisher m_fmarkerPub
void adjustMapData(nav_msgs::OccupancyGrid &map, const nav_msgs::MapMetaData &oldMapInfo) const
virtual void handleFreeNode(const OcTreeT::iterator &it)
hook that is called when traversing free nodes of the updated Octree
unsigned mapIdx(const octomap::OcTreeKey &key) const
nav_msgs::OccupancyGrid m_gridmap
octomap_msgs::BoundingBoxQuery BBXSrv
std_msgs::ColorRGBA m_colorFree
octomap::OcTreeKey m_updateBBXMin
virtual void insertScan(const tf::Point &sensorOrigin, const PCLPointCloud &ground, const PCLPointCloud &nonground)
update occupancy map with a scan labeled as ground and nonground. The scans should be in the global m...
ros::Publisher m_pointCloudPub
bool isInUpdateBBX(const OcTreeT::iterator &it) const
Test if key is within update area of map (2D, ignores height)
octomap::OcTreeKey m_updateBBXMax
ros::Publisher m_fullMapPub
double m_groundFilterDistance
virtual void handleOccupiedNode(const OcTreeT::iterator &it)
hook that is called when traversing occupied nodes of the updated Octree
unsigned mapIdx(int i, int j) const
ros::ServiceServer m_clearBBXService
tf::TransformListener m_tfListener
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointCloudSub
double m_groundFilterPlaneDistance
bool m_projectCompleteMap
virtual void handleOccupiedNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing occupied nodes in the updated area (updates 2D map projection her...
void reconfigureCallback(octomap_server::OctomapServerConfig &config, uint32_t level)
void publishFullOctoMap(const ros::Time &rostime=ros::Time::now()) const
virtual void handleNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing all nodes of the updated Octree in the updated area (does nothing...
ros::Publisher m_markerPub
virtual void handlePostNodeTraversal(const ros::Time &rostime)
hook that is called after traversing all nodes
std::string m_worldFrameId
boost::recursive_mutex m_config_mutex
virtual void update2DMap(const OcTreeT::iterator &it, bool occupied)
updates the downprojected 2D map as either occupied or free
std_msgs::ColorRGBA m_color
ros::Publisher m_binaryMapPub
octomap_server
Author(s): Armin Hornung
autogenerated on Mon Jan 2 2023 03:18:15