00001 #ifndef OCTOMAP_SERVER_OCTOMAP_SERVER
00002 #define OCTOMAP_SERVER_OCTOMAP_SERVER
00003
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042 #include <ros/ros.h>
00043 #include <visualization_msgs/MarkerArray.h>
00044 #include <std_msgs/ColorRGBA.h>
00045 #include <mapping_msgs/CollisionObject.h>
00046 #include <sensor_msgs/PointCloud2.h>
00047 #include <pcl/point_types.h>
00048 #include <pcl/ros/conversions.h>
00049 #include <pcl_ros/transforms.h>
00050 #include <tf/transform_listener.h>
00051 #include <tf/message_filter.h>
00052 #include <message_filters/subscriber.h>
00053 #include <octomap_ros/OctomapBinary.h>
00054 #include <octomap_ros/GetOctomap.h>
00055 #include <octomap_ros/OctomapROS.h>
00056
00057
00058 namespace octomap {
00059 class OctomapServer{
00060 public:
00061 OctomapServer();
00062 virtual ~OctomapServer();
00063 bool serviceCallback(octomap_ros::GetOctomap::Request &req,
00064 octomap_ros::GetOctomap::Response &res);
00065
00066 virtual void insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud);
00067
00068 bool loadInitialMap(const std::string& filename);
00069
00070 protected:
00071 void connectCallback(const ros::SingleSubscriberPublisher& pub);
00072 std_msgs::ColorRGBA heightMapColor(double h) const;
00073 void publishMap(const ros::Time& rostime = ros::Time::now());
00074 void publishMarkers(const ros::Time& rostime = ros::Time::now());
00075 void publishPointCloud(const ros::Time& rostime = ros::Time::now());
00076 void publishCollisionObject(const ros::Time& rostime = ros::Time::now());
00077 ros::NodeHandle m_nh;
00078 ros::Publisher m_markerPub, m_binaryMapPub, m_pointCloudPub, m_collisionObjectPub;
00079 message_filters::Subscriber<sensor_msgs::PointCloud2>* m_pointCloudSub;
00080 tf::MessageFilter<sensor_msgs::PointCloud2>* m_tfPointCloudSub;
00081 ros::ServiceServer m_service;
00082 tf::TransformListener m_tfListener;
00083
00084 OcTreeROS m_octoMap;
00085 double m_maxRange;
00086 std::string m_frameId;
00087 bool m_useHeightMap;
00088 std_msgs::ColorRGBA m_color;
00089 double m_colorFactor;
00090 double m_visMinZ;
00091 double m_visMaxZ;
00092 };
00093 }
00094
00095
00096 #endif