depth_cloud_display.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, 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_DEPTH_CLOUD_DISPLAY_H
31 #define RVIZ_DEPTH_CLOUD_DISPLAY_H
32 
33 #ifndef Q_MOC_RUN
34 #include <boost/shared_ptr.hpp>
35 #include <boost/thread/mutex.hpp>
36 
37 #include <ros/ros.h>
43 #include <tf2_ros/message_filter.h>
44 
50 
51 #include <rviz/display.h>
52 
54 #endif
55 
56 #include <QMap>
57 
58 using namespace message_filters::sync_policies;
59 
60 // Forward declarations
61 
62 namespace image_transport
63 {
64 class SubscriberFilter;
65 }
66 
67 namespace rviz
68 {
69 class EnumProperty;
70 class FloatProperty;
71 class BoolProperty;
72 class IntProperty;
73 
74 class MultiLayerDepth;
75 
77 {
78  Q_OBJECT
79 public:
80  RosFilteredTopicProperty(const QString& name = QString(),
81  const QString& default_value = QString(),
82  const QString& message_type = QString(),
83  const QString& description = QString(),
84  const QRegExp& filter = QRegExp(),
85  Property* parent = nullptr,
86  const char* changed_slot = nullptr,
87  QObject* receiver = nullptr)
88  : RosTopicProperty(name, default_value, message_type, description, parent, changed_slot, receiver)
89  , filter_(filter)
90  , filter_enabled_(true)
91  {
92  }
93 
94 public:
95  void enableFilter(bool enabled)
96  {
97  filter_enabled_ = enabled;
98  fillTopicList();
99  }
100 
101  QRegExp filter() const
102  {
103  return filter_;
104  }
105 
106 protected Q_SLOTS:
107  void fillTopicList() override
108  {
109  QStringList filtered_strings_;
110 
111  // Obtain list of available topics
112  RosTopicProperty::fillTopicList();
113  // Apply filter
114  if (filter_enabled_)
115  strings_ = strings_.filter(filter_);
116  }
117 
118 private:
119  QRegExp filter_;
121 };
122 
128 {
129  Q_OBJECT
130 public:
132  ~DepthCloudDisplay() override;
133 
134  void onInitialize() override;
135 
136  // Overrides from Display
137  void update(float wall_dt, float ros_dt) override;
138  void reset() override;
139  void setTopic(const QString& topic, const QString& datatype) override;
140 
141 protected Q_SLOTS:
142  void updateQueueSize();
144  void fillTransportOptionList(EnumProperty* property);
145 
146  // Property callbacks
147  virtual void updateTopic();
148  virtual void updateTopicFilter();
149  virtual void updateUseAutoSize();
150  virtual void updateAutoSizeFactor();
151  virtual void updateUseOcclusionCompensation();
152  virtual void updateOcclusionTimeOut();
153 
154 protected:
155  void scanForTransportSubscriberPlugins();
156 
157  typedef std::vector<rviz::PointCloud::Point> V_Point;
158 
159  virtual void processMessage(sensor_msgs::Image::ConstPtr msg);
160  virtual void processMessage(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImageConstPtr rgb_msg);
161  void caminfoCallback(sensor_msgs::CameraInfo::ConstPtr msg);
162 
163  // overrides from Display
164  void onEnable() override;
165  void onDisable() override;
166 
167  void fixedFrameChanged() override;
168 
169  void subscribe();
170  void unsubscribe();
171 
172  void clear();
173 
174  // thread-safe status updates
175  // add status update to global status list
176  void updateStatus(StatusProperty::Level level, const QString& name, const QString& text);
177 
178  // use global status list to update rviz plugin status
179  void setStatusList();
180 
182 
183  boost::mutex mutex_;
184 
185  // ROS image subscription & synchronization
186  boost::scoped_ptr<image_transport::ImageTransport> depthmap_it_;
189  boost::scoped_ptr<image_transport::ImageTransport> rgb_it_;
192  sensor_msgs::CameraInfo::ConstPtr cam_info_;
193  boost::mutex cam_info_mutex_;
194 
197 
199 
200  // RVIZ properties
211 
212  uint32_t queue_size_;
213 
215 
216  Ogre::Quaternion current_orientation_;
217  Ogre::Vector3 current_position_;
220 
222 
223  std::set<std::string> transport_plugin_types_;
224 };
225 
226 
227 } // namespace rviz
228 
229 #endif // RVIZ_DEPTHMAP_TO_POINTCLOUD_DISPLAY_H
Ogre::Quaternion current_orientation_
boost::shared_ptr< SynchronizerDepthColor > sync_depth_color_
boost::scoped_ptr< image_transport::ImageTransport > rgb_it_
RosFilteredTopicProperty(const QString &name=QString(), const QString &default_value=QString(), const QString &message_type=QString(), const QString &description=QString(), const QRegExp &filter=QRegExp(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
std::vector< rviz::PointCloud::Point > V_Point
FloatProperty * auto_size_factor_property_
A single element of a property tree, with a name, value, description, and possibly children...
Definition: property.h:100
MultiLayerDepth * ml_depth_data_
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
Property specialized to enforce floating point max/min.
sensor_msgs::CameraInfo::ConstPtr cam_info_
def default_value(type_)
boost::shared_ptr< image_transport::SubscriberFilter > depthmap_sub_
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:37
Displays a point cloud of type sensor_msgs::PointCloud.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::set< std::string > transport_plugin_types_
void subscribe()
boost::shared_ptr< tf2_ros::MessageFilter< sensor_msgs::Image > > depthmap_tf_filter_
description
boost::scoped_ptr< image_transport::ImageTransport > depthmap_it_
const char * datatype()
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::CameraInfo > > cam_info_sub_
RosFilteredTopicProperty * color_topic_property_
BoolProperty * use_occlusion_compensation_property_
PointCloudCommon * pointcloud_common_
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
EnumProperty * depth_transport_property_
FloatProperty * occlusion_shadow_timeout_property_
EnumProperty * color_transport_property_
boost::shared_ptr< image_transport::SubscriberFilter > rgb_sub_
void unsubscribe()
Enum property.
Definition: enum_property.h:46
BoolProperty * use_auto_size_property_
RosFilteredTopicProperty * depth_topic_property_


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:24