point_cloud_common.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
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  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef RVIZ_POINT_CLOUD_COMMON_H
31 #define RVIZ_POINT_CLOUD_COMMON_H
32 
33 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
34 #include <deque>
35 #include <queue>
36 #include <vector>
37 
38 #include <QObject>
39 #include <QList>
40 
41 #include <boost/shared_ptr.hpp>
42 #include <boost/thread/mutex.hpp>
43 #include <boost/thread/recursive_mutex.hpp>
44 
46 
48 
49 #include <sensor_msgs/PointCloud.h>
50 #include <sensor_msgs/PointCloud2.h>
51 
57 #endif
58 
59 namespace rviz
60 {
61 class BoolProperty;
62 class Display;
63 class DisplayContext;
64 class EnumProperty;
65 class FloatProperty;
66 struct IndexAndMessage;
71 
72 typedef std::vector<std::string> V_string;
73 
84 class PointCloudCommon : public QObject
85 {
86  Q_OBJECT
87 public:
88  struct CloudInfo
89  {
90  CloudInfo();
91  ~CloudInfo();
92 
93  // clear the point cloud, but keep selection handler around
94  void clear();
95 
97 
98  Ogre::SceneManager* manager_;
99 
100  sensor_msgs::PointCloud2ConstPtr message_;
101 
102  Ogre::SceneNode* scene_node_;
105 
106  std::vector<PointCloud::Point> transformed_points_;
107 
108  Ogre::Quaternion orientation_;
109  Ogre::Vector3 position_;
110  };
111 
113  typedef std::deque<CloudInfoPtr> D_CloudInfo;
114  typedef std::vector<CloudInfoPtr> V_CloudInfo;
115  typedef std::queue<CloudInfoPtr> Q_CloudInfo;
116  typedef std::list<CloudInfoPtr> L_CloudInfo;
117 
118  PointCloudCommon(Display* display);
119  ~PointCloudCommon() override;
120 
121  void initialize(DisplayContext* context, Ogre::SceneNode* scene_node);
122 
123  void fixedFrameChanged();
124  void reset();
125  void update(float wall_dt, float ros_dt);
126 
127  void addMessage(const sensor_msgs::PointCloudConstPtr& cloud);
128  void addMessage(const sensor_msgs::PointCloud2ConstPtr& cloud);
129 
131  {
132  return display_;
133  }
134 
136 
145 
146  void setAutoSize(bool auto_size);
147 
148 public Q_SLOTS:
149  void causeRetransform();
150 
151 private Q_SLOTS:
152  void updateSelectable();
153  void updateStyle();
154  void updateBillboardSize();
155  void updateAlpha();
156  void updateXyzTransformer();
157  void updateColorTransformer();
160 
161 private:
165  bool transformCloud(const CloudInfoPtr& cloud, bool fully_update_transformers);
166 
167  void processMessage(const sensor_msgs::PointCloud2ConstPtr& cloud);
168  void updateStatus();
169 
170  PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud);
171  PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud);
172  void updateTransformers(const sensor_msgs::PointCloud2ConstPtr& cloud);
173  void retransform();
174  void onTransformerOptions(V_string& ops, uint32_t mask);
175 
176  void loadTransformers();
177 
178  float getSelectionBoxSize();
179  void setPropertiesHidden(const QList<Property*>& props, bool hide);
180  void fillTransformerOptions(EnumProperty* prop, uint32_t mask);
181 
183 
184  Ogre::SceneNode* scene_node_;
185 
187  boost::mutex new_clouds_mutex_;
188 
190 
192  {
194  QList<Property*> xyz_props;
195  QList<Property*> color_props;
196 
197  std::string readable_name;
198  std::string lookup_name;
199  };
200  typedef std::map<std::string, TransformerInfo> M_TransformerInfo;
201 
202  boost::recursive_mutex transformers_mutex_;
207 
209 
212 
214 };
215 
217 {
218 public:
219  PointCloudSelectionHandler(float box_size,
220  PointCloudCommon::CloudInfo* cloud_info,
221  DisplayContext* context);
222  ~PointCloudSelectionHandler() override;
223 
224  void createProperties(const Picked& obj, Property* parent_property) override;
225  void destroyProperties(const Picked& obj, Property* parent_property) override;
226 
227  bool needsAdditionalRenderPass(uint32_t pass) override
228  {
229  return pass < 2;
230  }
231 
232  void preRenderPass(uint32_t pass) override;
233  void postRenderPass(uint32_t pass) override;
234 
235  void onSelect(const Picked& obj) override;
236  void onDeselect(const Picked& obj) override;
237 
238  void getAABBs(const Picked& obj, V_AABB& aabbs) override;
239 
240  void setBoxSize(float size)
241  {
242  box_size_ = size;
243  }
244 
246  {
247  return !boxes_.empty();
248  }
249 
250 private:
252  QHash<IndexAndMessage, Property*> property_hash_;
253  float box_size_;
254 };
255 
256 } // namespace rviz
257 
258 #endif // RVIZ_POINT_CLOUD_COMMON_H
rviz::PointCloudSelectionHandler
Definition: point_cloud_common.h:216
rviz::PointCloudCommon::M_TransformerInfo
std::map< std::string, TransformerInfo > M_TransformerInfo
Definition: point_cloud_common.h:200
rviz::PointCloudSelectionHandler::getAABBs
void getAABBs(const Picked &obj, V_AABB &aabbs) override
Definition: point_cloud_common.cpp:241
rviz::PointCloudCommon::updateBillboardSize
void updateBillboardSize()
Definition: point_cloud_common.cpp:488
rviz::PointCloudCommon::CloudInfo::position_
Ogre::Vector3 position_
Definition: point_cloud_common.h:109
rviz::PointCloudSelectionHandlerPtr
boost::shared_ptr< PointCloudSelectionHandler > PointCloudSelectionHandlerPtr
Definition: point_cloud_common.h:67
rviz::PointCloudCommon::setAutoSize
void setAutoSize(bool auto_size)
Definition: point_cloud_common.cpp:425
rviz::PointCloudCommon::CloudInfoPtr
boost::shared_ptr< CloudInfo > CloudInfoPtr
Definition: point_cloud_common.h:112
rviz::PointCloudSelectionHandler::property_hash_
QHash< IndexAndMessage, Property * > property_hash_
Definition: point_cloud_common.h:252
rviz::PointCloudSelectionHandler::destroyProperties
void destroyProperties(const Picked &obj, Property *parent_property) override
Destroy all properties for the given picked object(s).
Definition: point_cloud_common.cpp:211
rviz::PointCloudCommon::updateSelectable
void updateSelectable()
Definition: point_cloud_common.cpp:444
rviz::PointCloudCommon::xyz_transformer_property_
EnumProperty * xyz_transformer_property_
Definition: point_cloud_common.h:141
boost::shared_ptr< PointCloudSelectionHandler >
rviz::PointCloudCommon::initialize
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
Definition: point_cloud_common.cpp:366
rviz::PointCloudCommon::CloudInfo::receive_time_
ros::Time receive_time_
Definition: point_cloud_common.h:96
forwards.h
rviz::PointCloudCommon::update
void update(float wall_dt, float ros_dt)
Definition: point_cloud_common.cpp:520
rviz::PointCloudCommon::getSelectionBoxSize
float getSelectionBoxSize()
Definition: point_cloud_common.cpp:991
rviz::PointCloudCommon::TransformerInfo
Definition: point_cloud_common.h:191
rviz::PointCloudCommon::CloudInfo::message_
sensor_msgs::PointCloud2ConstPtr message_
Definition: point_cloud_common.h:100
rviz::BoolProperty
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
rviz::PointCloudCommon::L_CloudInfo
std::list< CloudInfoPtr > L_CloudInfo
Definition: point_cloud_common.h:116
rviz::PointCloudCommon::updateTransformers
void updateTransformers(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: point_cloud_common.cpp:655
rviz::PointCloudCommon::setXyzTransformerOptions
void setXyzTransformerOptions(EnumProperty *prop)
Definition: point_cloud_common.cpp:956
rviz::PointCloudSelectionHandler::preRenderPass
void preRenderPass(uint32_t pass) override
Definition: point_cloud_common.cpp:94
point_cloud.h
rviz::PointCloudCommon::addMessage
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
Definition: point_cloud_common.cpp:939
rviz::PointCloudCommon::CloudInfo::manager_
Ogre::SceneManager * manager_
Definition: point_cloud_common.h:98
selection_manager.h
rviz::PointCloudSelectionHandler::PointCloudSelectionHandler
PointCloudSelectionHandler(float box_size, PointCloudCommon::CloudInfo *cloud_info, DisplayContext *context)
Definition: point_cloud_common.cpp:77
rviz::PointCloudCommon::selectable_property_
BoolProperty * selectable_property_
Definition: point_cloud_common.h:137
rviz::PointCloudCommon::new_clouds_mutex_
boost::mutex new_clouds_mutex_
Definition: point_cloud_common.h:187
rviz::PointCloudSelectionHandler::setBoxSize
void setBoxSize(float size)
Definition: point_cloud_common.h:240
rviz::PointCloudCommon::TransformerInfo::readable_name
std::string readable_name
Definition: point_cloud_common.h:197
rviz::PointCloudCommon::updateStatus
void updateStatus()
Definition: point_cloud_common.cpp:725
rviz::PointCloudCommon::point_world_size_property_
FloatProperty * point_world_size_property_
Definition: point_cloud_common.h:138
rviz::PointCloudCommon::style_property_
EnumProperty * style_property_
Definition: point_cloud_common.h:143
rviz::PointCloudSelectionHandler::hasSelections
bool hasSelections()
Definition: point_cloud_common.h:245
rviz::PointCloudCommon::cloud_infos_
D_CloudInfo cloud_infos_
Definition: point_cloud_common.h:182
rviz::PointCloudCommon::CloudInfo
Definition: point_cloud_common.h:88
rviz::PointCloudCommon::TransformerInfo::xyz_props
QList< Property * > xyz_props
Definition: point_cloud_common.h:194
rviz::Display
Definition: display.h:63
rviz::PointCloudCommon::getXYZTransformer
PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: point_cloud_common.cpp:769
rviz::EnumProperty
Enum property.
Definition: enum_property.h:46
rviz::PointCloudCommon::display_
Display * display_
Definition: point_cloud_common.h:210
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::PointCloudCommon::new_color_transformer_
bool new_color_transformer_
Definition: point_cloud_common.h:205
rviz::Picked
Definition: forwards.h:53
rviz::Property
A single element of a property tree, with a name, value, description, and possibly children.
Definition: property.h:100
rviz::PointCloudCommon::CloudInfo::~CloudInfo
~CloudInfo()
Definition: point_cloud_common.cpp:294
rviz::PointCloudCommon::updateXyzTransformer
void updateXyzTransformer()
Definition: point_cloud_common.cpp:746
rviz::PointCloudCommon::new_xyz_transformer_
bool new_xyz_transformer_
Definition: point_cloud_common.h:204
rviz::V_string
std::vector< std::string > V_string
Definition: effort_display.h:72
rviz::PointCloudCommon::context_
DisplayContext * context_
Definition: point_cloud_common.h:211
rviz::PointCloudCommon::getDisplay
Display * getDisplay()
Definition: point_cloud_common.h:130
rviz::PointCloudCommon::needs_retransform_
bool needs_retransform_
Definition: point_cloud_common.h:206
rviz::PointCloudCommon::retransform
void retransform()
Definition: point_cloud_common.cpp:803
rviz::PointCloudSelectionHandler::createProperties
void createProperties(const Picked &obj, Property *parent_property) override
Override to create properties of the given picked object(s).
Definition: point_cloud_common.cpp:138
rviz::PointCloudCommon::point_pixel_size_property_
FloatProperty * point_pixel_size_property_
Definition: point_cloud_common.h:139
rviz
Definition: add_display_dialog.cpp:54
color_property.h
rviz::PointCloudCommon::setPropertiesHidden
void setPropertiesHidden(const QList< Property * > &props, bool hide)
Definition: point_cloud_common.cpp:647
rviz::PointCloudCommon::processMessage
void processMessage(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: point_cloud_common.cpp:732
rviz::PointCloudSelectionHandler::onDeselect
void onDeselect(const Picked &obj) override
Definition: point_cloud_common.cpp:278
rviz::PointCloudCommon::V_CloudInfo
std::vector< CloudInfoPtr > V_CloudInfo
Definition: point_cloud_common.h:114
rviz::PointCloudSelectionHandler::postRenderPass
void postRenderPass(uint32_t pass) override
Definition: point_cloud_common.cpp:111
rviz::PointCloudTransformer
Definition: point_cloud_transformer.h:60
rviz::PointCloudCommon::TransformerInfo::transformer
PointCloudTransformerPtr transformer
Definition: point_cloud_common.h:193
rviz::PointCloudCommon::transformers_mutex_
boost::recursive_mutex transformers_mutex_
Definition: point_cloud_common.h:202
rviz::PointCloudCommon::onTransformerOptions
void onTransformerOptions(V_string &ops, uint32_t mask)
rviz::PointCloudTransformerPtr
boost::shared_ptr< PointCloudTransformer > PointCloudTransformerPtr
Definition: point_cloud_common.h:69
rviz::PointCloudCommon::~PointCloudCommon
~PointCloudCommon() override
Definition: point_cloud_common.cpp:381
rviz::PointCloudCommon::loadTransformers
void loadTransformers()
Definition: point_cloud_common.cpp:389
pluginlib::ClassLoader
rviz::PointCloudCommon
Displays a point cloud of type sensor_msgs::PointCloud.
Definition: point_cloud_common.h:84
class_loader.hpp
rviz::SelectionHandler::boxes_
M_HandleToBox boxes_
Definition: selection_handler.h:154
rviz::DisplayContext
Pure-virtual base class for objects which give Display subclasses context in which to work.
Definition: display_context.h:81
rviz::PointCloudCommon::updateAlpha
void updateAlpha()
Definition: point_cloud_common.cpp:435
rviz::PointCloudCommon::PointCloudCommon
PointCloudCommon(Display *display)
Definition: point_cloud_common.cpp:308
rviz::PointCloudCommon::CloudInfo::transformed_points_
std::vector< PointCloud::Point > transformed_points_
Definition: point_cloud_common.h:106
rviz::PointCloudCommon::auto_size_
bool auto_size_
Definition: point_cloud_common.h:135
rviz::V_AABB
std::vector< Ogre::AxisAlignedBox > V_AABB
Definition: selection_handler.h:60
rviz::PointCloudCommon::color_transformer_property_
EnumProperty * color_transformer_property_
Definition: point_cloud_common.h:142
rviz::PointCloudCommon::TransformerInfo::lookup_name
std::string lookup_name
Definition: point_cloud_common.h:198
ros::Time
rviz::PointCloudCommon::transformCloud
bool transformCloud(const CloudInfoPtr &cloud, bool fully_update_transformers)
Transforms the cloud into the correct frame, and sets up our renderable cloud.
Definition: point_cloud_common.cpp:819
rviz::PointCloudSelectionHandler::needsAdditionalRenderPass
bool needsAdditionalRenderPass(uint32_t pass) override
Definition: point_cloud_common.h:227
rviz::PointCloudCommon::CloudInfo::selection_handler_
PointCloudSelectionHandlerPtr selection_handler_
Definition: point_cloud_common.h:104
rviz::PointCloudCommon::fillTransformerOptions
void fillTransformerOptions(EnumProperty *prop, uint32_t mask)
Definition: point_cloud_common.cpp:966
rviz::PointCloudCommon::updateColorTransformer
void updateColorTransformer()
Definition: point_cloud_common.cpp:757
rviz::SelectionHandler
Definition: selection_handler.h:64
rviz::PointCloudCommon::D_CloudInfo
std::deque< CloudInfoPtr > D_CloudInfo
Definition: point_cloud_common.h:113
rviz::PointCloudCommon::CloudInfo::orientation_
Ogre::Quaternion orientation_
Definition: point_cloud_common.h:108
rviz::PointCloudCommon::setColorTransformerOptions
void setColorTransformerOptions(EnumProperty *prop)
Definition: point_cloud_common.cpp:961
rviz::PointCloudCommon::Q_CloudInfo
std::queue< CloudInfoPtr > Q_CloudInfo
Definition: point_cloud_common.h:115
rviz::PointCloudCommon::updateStyle
void updateStyle()
Definition: point_cloud_common.cpp:468
rviz::PointCloudCommon::transformers_
M_TransformerInfo transformers_
Definition: point_cloud_common.h:203
rviz::PointCloudCommon::causeRetransform
void causeRetransform()
Definition: point_cloud_common.cpp:515
rviz::PointCloudCommon::obsolete_cloud_infos_
L_CloudInfo obsolete_cloud_infos_
Definition: point_cloud_common.h:189
rviz::PointCloudCommon::reset
void reset()
Definition: point_cloud_common.cpp:508
point_cloud_transformer.h
rviz::PointCloudCommon::CloudInfo::cloud_
boost::shared_ptr< PointCloud > cloud_
Definition: point_cloud_common.h:103
rviz::PointCloudCommon::alpha_property_
FloatProperty * alpha_property_
Definition: point_cloud_common.h:140
rviz::PointCloudSelectionHandler::cloud_info_
PointCloudCommon::CloudInfo * cloud_info_
Definition: point_cloud_common.h:251
rviz::PointCloudCommon::getColorTransformer
PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: point_cloud_common.cpp:786
rviz::PointCloudCommon::transformer_class_loader_
pluginlib::ClassLoader< PointCloudTransformer > * transformer_class_loader_
Definition: point_cloud_common.h:208
rviz::PointCloudCommon::CloudInfo::scene_node_
Ogre::SceneNode * scene_node_
Definition: point_cloud_common.h:102
rviz::PointCloudCommon::CloudInfo::CloudInfo
CloudInfo()
Definition: point_cloud_common.cpp:290
rviz::PointCloudSelectionHandler::box_size_
float box_size_
Definition: point_cloud_common.h:253
rviz::PointCloudCommon::fixedFrameChanged
void fixedFrameChanged()
Definition: point_cloud_common.cpp:951
rviz::PointCloudSelectionHandler::onSelect
void onSelect(const Picked &obj) override
Definition: point_cloud_common.cpp:257
time_sequencer.h
rviz::PointCloudCommon::CloudInfo::clear
void clear()
Definition: point_cloud_common.cpp:299
rviz::PointCloudCommon::decay_time_property_
FloatProperty * decay_time_property_
Definition: point_cloud_common.h:144
rviz::PointCloudSelectionHandler::~PointCloudSelectionHandler
~PointCloudSelectionHandler() override
Definition: point_cloud_common.cpp:84
rviz::PointCloudCommon::scene_node_
Ogre::SceneNode * scene_node_
Definition: point_cloud_common.h:184
rviz::PointCloudCommon::TransformerInfo::color_props
QList< Property * > color_props
Definition: point_cloud_common.h:195
rviz::PointCloudCommon::new_cloud_infos_
V_CloudInfo new_cloud_infos_
Definition: point_cloud_common.h:186


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Dec 13 2024 03:31:02