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 
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 
125 
126 public Q_SLOTS:
127  void causeRetransform();
128 
129 private Q_SLOTS:
130  void updateStyle();
131  void updateBillboardSize();
132  void updateAlpha();
133  void updateXyzTransformer();
134  void updateColorTransformer();
135  void setXyzTransformerOptions( EnumProperty* prop );
136  void setColorTransformerOptions( EnumProperty* prop );
137  void updateCloudParameters();
138  void downloadNamespaceChanged();
139  void downloadMap();
140  void downloadGraph();
141 
142 protected:
144  virtual void onInitialize();
145 
147  virtual void processMessage( const rtabmap_ros::MapDataConstPtr& cloud );
148 
149 private:
150  void downloadMap(bool graphOnly);
151  void processMapData(const rtabmap_ros::MapData& map);
152 
156  bool transformCloud(const CloudInfoPtr& cloud, bool fully_update_transformers);
157 
158  rviz::PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud);
159  rviz::PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud);
160  void updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud );
161  void retransform();
162 
163  void loadTransformers();
164 
165  void setPropertiesHidden( const QList<Property*>& props, bool hide );
166  void fillTransformerOptions( rviz::EnumProperty* prop, uint32_t mask );
167 
168 private:
172 
173  std::map<int, CloudInfoPtr> cloud_infos_;
174 
175  std::map<int, CloudInfoPtr> new_cloud_infos_;
176  boost::mutex new_clouds_mutex_;
177 
178  std::set<int> nodeDataReceived_;
179  bool fromScan_;
180 
181  std::map<int, rtabmap::Transform> current_map_;
182  boost::mutex current_map_mutex_;
184 
186 
188  {
190  QList<Property*> xyz_props;
191  QList<Property*> color_props;
192 
193  std::string readable_name;
194  std::string lookup_name;
195  };
196  typedef std::map<std::string, TransformerInfo> M_TransformerInfo;
197 
198  boost::recursive_mutex transformers_mutex_;
199  M_TransformerInfo transformers_;
203 
205 };
206 
207 } // namespace rtabmap_ros
208 
209 #endif
GLM_FUNC_DECL genIType mask(genIType const &count)
rviz::StringProperty * download_namespace
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_
ros::Publisher republishNodeDataPub_
rviz::BoolProperty * download_graph_


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40