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 #ifndef _pointcloud_to_octomap_alg_h_
00026 #define _pointcloud_to_octomap_alg_h_
00027
00028 #include <iri_pointcloud_to_octomap/PointcloudToOctomapConfig.h>
00029 #include "mutex.h"
00030 #include <sensor_msgs/PointCloud2.h>
00031 #include <octomap/octomap.h>
00032 #include <octomap/OcTree.h>
00033 #include <octomap/ColorOcTree.h>
00034
00035
00036
00042 class PointcloudToOctomapAlgorithm
00043 {
00044 protected:
00051 CMutex alg_mutex_;
00052
00053
00054
00055 public:
00062 typedef iri_pointcloud_to_octomap::PointcloudToOctomapConfig Config;
00063
00070 Config config_;
00071
00080 PointcloudToOctomapAlgorithm(void);
00081
00087 void lock(void) { alg_mutex_.enter(); };
00088
00094 void unlock(void) { alg_mutex_.exit(); };
00095
00103 bool try_enter(void) { return alg_mutex_.try_enter(); };
00104
00116 void config_update(Config& new_cfg, uint32_t level=0);
00117
00118
00119
00120 bool isRunning(const std::string& file_name, const sensor_msgs::PointCloud2::ConstPtr& msg, const octomap::point3d& sensor_origin, const octomap::pose6d& frame_origin);
00121
00128 ~PointcloudToOctomapAlgorithm(void);
00129 };
00130
00131 #endif