MapCloudDisplay.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef MAP_CLOUD_DISPLAY_H
29 #define MAP_CLOUD_DISPLAY_H
30 
31 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
32 
33 #include <deque>
34 #include <queue>
35 #include <vector>
36 
37 #include <rtabmap_ros/MapData.h>
38 #include <rtabmap/core/Transform.h>
39 
40 #include <pluginlib/class_loader.h>
41 #include <sensor_msgs/PointCloud2.h>
42 
43 #include <ros/callback_queue.h>
44 
48 
49 #endif
50 
51 namespace rviz {
52 class IntProperty;
53 class BoolProperty;
54 class EnumProperty;
55 class FloatProperty;
58 typedef std::vector<std::string> V_string;
59 }
60 
61 using namespace rviz;
62 
63 namespace rtabmap_ros
64 {
65 
66 class PointCloudCommon;
67 
76 class MapCloudDisplay: public rviz::MessageFilterDisplay<rtabmap_ros::MapData>
77 {
78 Q_OBJECT
79 public:
80  struct CloudInfo
81  {
82  CloudInfo();
83  ~CloudInfo();
84 
85  // clear the point cloud, but keep selection handler around
86  void clear();
87 
88  Ogre::SceneManager *manager_;
89 
90  sensor_msgs::PointCloud2ConstPtr message_;
92  int id_;
93 
94  Ogre::SceneNode *scene_node_;
96 
97  std::vector<rviz::PointCloud::Point> transformed_points_;
98  };
100 
101  MapCloudDisplay();
102  virtual ~MapCloudDisplay();
103 
104  virtual void reset();
105  virtual void update( float wall_dt, float ros_dt );
106 
124 
125 public Q_SLOTS:
126  void causeRetransform();
127 
128 private Q_SLOTS:
129  void updateStyle();
130  void updateBillboardSize();
131  void updateAlpha();
132  void updateXyzTransformer();
133  void updateColorTransformer();
134  void setXyzTransformerOptions( EnumProperty* prop );
135  void setColorTransformerOptions( EnumProperty* prop );
136  void updateCloudParameters();
137  void downloadMap();
138  void downloadGraph();
139 
140 protected:
142  virtual void onInitialize();
143 
145  virtual void processMessage( const rtabmap_ros::MapDataConstPtr& cloud );
146 
147 private:
148  void processMapData(const rtabmap_ros::MapData& map);
149 
153  bool transformCloud(const CloudInfoPtr& cloud, bool fully_update_transformers);
154 
155  rviz::PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud);
156  rviz::PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud);
157  void updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud );
158  void retransform();
159 
160  void loadTransformers();
161 
162  void setPropertiesHidden( const QList<Property*>& props, bool hide );
163  void fillTransformerOptions( rviz::EnumProperty* prop, uint32_t mask );
164 
165 private:
168 
169  std::map<int, CloudInfoPtr> cloud_infos_;
170 
171  std::map<int, CloudInfoPtr> new_cloud_infos_;
172  boost::mutex new_clouds_mutex_;
173 
174  std::map<int, rtabmap::Transform> current_map_;
175  boost::mutex current_map_mutex_;
176 
178 
180  {
182  QList<Property*> xyz_props;
183  QList<Property*> color_props;
184 
185  std::string readable_name;
186  std::string lookup_name;
187  };
188  typedef std::map<std::string, TransformerInfo> M_TransformerInfo;
189 
190  boost::recursive_mutex transformers_mutex_;
191  M_TransformerInfo transformers_;
195 
197 };
198 
199 } // namespace rtabmap_ros
200 
201 #endif
GLM_FUNC_DECL genIType mask(genIType const &count)
rviz::EnumProperty * style_property_
pluginlib::ClassLoader< rviz::PointCloudTransformer > * transformer_class_loader_
Displays point clouds from rtabmap::MapData.
rviz::FloatProperty * cloud_voxel_size_
rviz::FloatProperty * cloud_max_depth_
std::map< std::string, TransformerInfo > M_TransformerInfo
bool update(const T &new_val, T &my_val)
rviz::IntProperty * cloud_decimation_
rviz::EnumProperty * xyz_transformer_property_
rviz::FloatProperty * cloud_filter_ceiling_height_
rviz::FloatProperty * alpha_property_
std::map< int, CloudInfoPtr > cloud_infos_
rviz::FloatProperty * point_pixel_size_property_
M_TransformerInfo transformers_
rviz::FloatProperty * node_filtering_radius_
rviz::BoolProperty * cloud_from_scan_
std::map< int, rtabmap::Transform > current_map_
rviz::BoolProperty * download_map_
boost::shared_ptr< PointCloudTransformer > PointCloudTransformerPtr
rviz::PointCloudTransformerPtr transformer
sensor_msgs::PointCloud2ConstPtr message_
rviz::FloatProperty * node_filtering_angle_
rviz::FloatProperty * point_world_size_property_
boost::recursive_mutex transformers_mutex_
rviz::FloatProperty * cloud_min_depth_
std::map< int, CloudInfoPtr > new_cloud_infos_
boost::shared_ptr< rviz::PointCloud > cloud_
std::vector< std::string > V_string
detail::uint32 uint32_t
rviz::FloatProperty * cloud_filter_floor_height_
boost::shared_ptr< CloudInfo > CloudInfoPtr
rviz::EnumProperty * color_transformer_property_
std::vector< rviz::PointCloud::Point > transformed_points_
rviz::BoolProperty * download_graph_


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19