Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef OCTOMAP_SERVER_OCTOMAPSERVER_H
00031 #define OCTOMAP_SERVER_OCTOMAPSERVER_H
00032
00033 #include <ros/ros.h>
00034 #include <visualization_msgs/MarkerArray.h>
00035 #include <nav_msgs/OccupancyGrid.h>
00036 #include <std_msgs/ColorRGBA.h>
00037
00038
00039
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include <std_srvs/Empty.h>
00042 #include <dynamic_reconfigure/server.h>
00043 #include <octomap_tensor_field/OctomapServerConfig.h>
00044
00045 #include <pcl/point_types.h>
00046 #include <pcl/conversions.h>
00047 #include <pcl_ros/transforms.h>
00048 #include <pcl/sample_consensus/method_types.h>
00049 #include <pcl/sample_consensus/model_types.h>
00050 #include <pcl/segmentation/sac_segmentation.h>
00051 #include <pcl/io/pcd_io.h>
00052 #include <pcl/filters/extract_indices.h>
00053 #include <pcl/filters/passthrough.h>
00054 #include <pcl_conversions/pcl_conversions.h>
00055
00056
00057 #include <tf/transform_listener.h>
00058 #include <tf/message_filter.h>
00059 #include <message_filters/subscriber.h>
00060 #include <octomap_msgs/Octomap.h>
00061 #include <octomap_msgs/GetOctomap.h>
00062 #include <octomap_msgs/BoundingBoxQuery.h>
00063 #include <octomap_msgs/conversions.h>
00064
00065 #include <octomap_ros/conversions.h>
00066 #include <octomap/octomap.h>
00067 #include <octomap/OcTreeKey.h>
00068 #include <std_msgs/Float64MultiArray.h>
00069
00070 #define COLOR_OCTOMAP_SERVER // turned off here, turned on identical ColorOctomapServer.h - easier maintenance, only maintain OctomapServer and then copy and paste to ColorOctomapServer and change define. There are prettier ways to do this, but this works for now
00071
00072
00073 #include "octomap_tensor_field/MyOcTree.h"
00074
00075
00076 #ifdef COLOR_OCTOMAP_SERVER
00077 #include <octomap/ColorOcTree.h>
00078 #endif
00079
00080 namespace octomap_server {
00081 class OctomapServer {
00082
00083 public:
00084 #ifdef COLOR_OCTOMAP_SERVER
00085 typedef pcl::PointXYZRGB PCLPoint;
00086 typedef pcl::PointCloud<pcl::PointXYZRGB> PCLPointCloud;
00087 typedef octomap::ColorOcTree OcTreeT;
00088 #else
00089 typedef pcl::PointXYZ PCLPoint;
00090 typedef pcl::PointCloud<pcl::PointXYZ> PCLPointCloud;
00091 typedef octomap::OcTree OcTreeT;
00092 #endif
00093 typedef octomap_msgs::GetOctomap OctomapSrv;
00094 typedef octomap_msgs::BoundingBoxQuery BBXSrv;
00095
00096 OctomapServer(ros::NodeHandle private_nh_ = ros::NodeHandle("~"));
00097 virtual ~OctomapServer();
00098 virtual bool octomapBinarySrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res);
00099 virtual bool octomapFullSrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res);
00100 bool clearBBXSrv(BBXSrv::Request& req, BBXSrv::Response& resp);
00101 bool resetSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp);
00102
00103 virtual void insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud);
00104 virtual bool openFile(const std::string& filename);
00105
00106 protected:
00107 inline static void updateMinKey(const octomap::OcTreeKey& in, octomap::OcTreeKey& min) {
00108 for (unsigned i = 0; i < 3; ++i)
00109 min[i] = std::min(in[i], min[i]);
00110 };
00111
00112 inline static void updateMaxKey(const octomap::OcTreeKey& in, octomap::OcTreeKey& max) {
00113 for (unsigned i = 0; i < 3; ++i)
00114 max[i] = std::max(in[i], max[i]);
00115 };
00116
00118 inline bool isInUpdateBBX(const OcTreeT::iterator& it) const {
00119
00120 unsigned voxelWidth = (1 << (m_maxTreeDepth - it.getDepth()));
00121 octomap::OcTreeKey key = it.getIndexKey();
00122 return (key[0] + voxelWidth >= m_updateBBXMin[0]
00123 && key[1] + voxelWidth >= m_updateBBXMin[1]
00124 && key[0] <= m_updateBBXMax[0]
00125 && key[1] <= m_updateBBXMax[1]);
00126 }
00127
00128 void reconfigureCallback(octomap_server::OctomapServerConfig& config, uint32_t level);
00129 void publishBinaryOctoMap(const ros::Time& rostime = ros::Time::now()) const;
00130 void publishFullOctoMap(const ros::Time& rostime = ros::Time::now()) const;
00131 void publishAll(const ros::Time& rostime = ros::Time::now());
00132
00141 virtual void insertScan(const tf::Point& sensorOrigin, const PCLPointCloud& ground, const PCLPointCloud& nonground);
00142
00144 void filterGroundPlane(const PCLPointCloud& pc, PCLPointCloud& ground, PCLPointCloud& nonground) const;
00145
00151 bool isSpeckleNode(const octomap::OcTreeKey& key) const;
00152
00154 virtual void handlePreNodeTraversal(const ros::Time& rostime);
00155
00157 virtual void handleNode(const OcTreeT::iterator& it) {};
00158
00160 virtual void handleNodeInBBX(const OcTreeT::iterator& it) {};
00161
00163 virtual void handleOccupiedNode(const OcTreeT::iterator& it);
00164
00166 virtual void handleOccupiedNodeInBBX(const OcTreeT::iterator& it);
00167
00169 virtual void handleFreeNode(const OcTreeT::iterator& it);
00170
00172 virtual void handleFreeNodeInBBX(const OcTreeT::iterator& it);
00173
00175 virtual void handlePostNodeTraversal(const ros::Time& rostime);
00176
00178 virtual void update2DMap(const OcTreeT::iterator& it, bool occupied);
00179
00180 inline unsigned mapIdx(int i, int j) const {
00181 return m_gridmap.info.width * j + i;
00182 }
00183
00184 inline unsigned mapIdx(const octomap::OcTreeKey& key) const {
00185 return mapIdx((key[0] - m_paddedMinKey[0]) / m_multires2DScale,
00186 (key[1] - m_paddedMinKey[1]) / m_multires2DScale);
00187
00188 }
00189
00196 void adjustMapData(nav_msgs::OccupancyGrid& map, const nav_msgs::MapMetaData& oldMapInfo) const;
00197
00198 inline bool mapChanged(const nav_msgs::MapMetaData& oldMapInfo, const nav_msgs::MapMetaData& newMapInfo) {
00199 return ( oldMapInfo.height != newMapInfo.height
00200 || oldMapInfo.width != newMapInfo.width
00201 || oldMapInfo.origin.position.x != newMapInfo.origin.position.x
00202 || oldMapInfo.origin.position.y != newMapInfo.origin.position.y);
00203 }
00204
00205 static std_msgs::ColorRGBA heightMapColor(double h);
00206 ros::NodeHandle m_nh;
00207
00208 ros::Publisher m_frontiermarkerPub;
00209
00210 std_msgs::Float64MultiArray m_frontier_points;
00211 ros::Publisher m_frontierPointsPub;
00212
00213
00214 ros::Publisher m_markerPub, m_binaryMapPub, m_fullMapPub, m_pointCloudPub, m_collisionObjectPub, m_mapPub, m_cmapPub, m_fmapPub, m_fmarkerPub;
00215 message_filters::Subscriber<sensor_msgs::PointCloud2>* m_pointCloudSub;
00216 tf::MessageFilter<sensor_msgs::PointCloud2>* m_tfPointCloudSub;
00217 ros::ServiceServer m_octomapBinaryService, m_octomapFullService, m_clearBBXService, m_resetService;
00218 tf::TransformListener m_tfListener;
00219 dynamic_reconfigure::Server<OctomapServerConfig> m_reconfigureServer;
00220
00221 OcTreeT* m_octree;
00222 octomap::KeyRay m_keyRay;
00223 octomap::OcTreeKey m_updateBBXMin;
00224 octomap::OcTreeKey m_updateBBXMax;
00225
00226 double m_maxRange;
00227 std::string m_worldFrameId;
00228 std::string m_baseFrameId;
00229 bool m_useHeightMap;
00230 std_msgs::ColorRGBA m_color;
00231 std_msgs::ColorRGBA m_colorFree;
00232 double m_colorFactor;
00233
00234 bool m_latchedTopics;
00235 bool m_publishFreeSpace;
00236
00237 bool m_publishFrontierSpace;
00238
00239
00240 double m_res;
00241 unsigned m_treeDepth;
00242 unsigned m_maxTreeDepth;
00243
00244 double m_pointcloudMinZ;
00245 double m_pointcloudMaxZ;
00246 double m_occupancyMinZ;
00247 double m_occupancyMaxZ;
00248 double m_minSizeX;
00249 double m_minSizeY;
00250 bool m_filterSpeckles;
00251
00252 bool m_filterGroundPlane;
00253 double m_groundFilterDistance;
00254 double m_groundFilterAngle;
00255 double m_groundFilterPlaneDistance;
00256
00257 bool m_compressMap;
00258
00259
00260 bool m_incrementalUpdate;
00261 nav_msgs::OccupancyGrid m_gridmap;
00262 bool m_publish2DMap;
00263 bool m_mapOriginChanged;
00264 octomap::OcTreeKey m_paddedMinKey;
00265 unsigned m_multires2DScale;
00266 bool m_projectCompleteMap;
00267 bool m_useColoredMap;
00268 };
00269 }
00270
00271 #endif