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 #include <QtCore/QRegularExpression>
58 
59 using namespace message_filters::sync_policies;
60 
61 // Forward declarations
62 
63 namespace image_transport
64 {
65 class SubscriberFilter;
66 }
67 
68 namespace rviz
69 {
70 class EnumProperty;
71 class FloatProperty;
72 class BoolProperty;
73 class IntProperty;
74 
75 class MultiLayerDepth;
76 
78 {
79  Q_OBJECT
80 public:
81  RosFilteredTopicProperty(const QString& name = QString(),
82  const QString& default_value = QString(),
83  const QString& message_type = QString(),
84  const QString& description = QString(),
85  const QRegularExpression& filter = QRegularExpression(),
86  Property* parent = nullptr)
87  : RosTopicProperty(name, default_value, message_type, description, parent)
88  , filter_(filter)
89  , filter_enabled_(true)
90  {
91  }
92 
93  template <typename Func, typename R>
94  RosFilteredTopicProperty(const QString& name,
95  const QString& default_value,
96  const QString& message_type,
97  const QString& description,
98  const QRegularExpression& filter,
99  Property* parent,
100  Func&& changed_slot,
101  const R* receiver)
102  : RosFilteredTopicProperty(name, default_value, message_type, description, filter, parent)
103  {
104  connect(receiver, std::forward<Func>(changed_slot));
105  }
106 
107  // this variant is required to allow omitting the receiver argument
108  template <typename Func, typename P>
109  RosFilteredTopicProperty(const QString& name,
110  const QString& default_value,
111  const QString& message_type,
112  const QString& description,
113  const QRegularExpression& filter,
114  P* parent,
115  Func&& changed_slot)
116  : RosFilteredTopicProperty(name, default_value, message_type, description, filter, parent)
117  {
118  connect(parent, std::forward<Func>(changed_slot));
119  }
120 
121 public:
122  void enableFilter(bool enabled)
123  {
124  filter_enabled_ = enabled;
125  fillTopicList();
126  }
127 
128  QRegularExpression filter() const
129  {
130  return filter_;
131  }
132 
133 protected Q_SLOTS:
134  void fillTopicList() override
135  {
136  QStringList filtered_strings_;
137 
138  // Obtain list of available topics
139  RosTopicProperty::fillTopicList();
140  // Apply filter
141  if (filter_enabled_)
142  strings_ = strings_.filter(filter_);
143  }
144 
145 private:
146  QRegularExpression filter_;
148 };
149 
155 {
156  Q_OBJECT
157 public:
159  ~DepthCloudDisplay() override;
160 
161  void onInitialize() override;
162 
163  // Overrides from Display
164  void update(float wall_dt, float ros_dt) override;
165  void reset() override;
166  void setTopic(const QString& topic, const QString& datatype) override;
167 
168 protected Q_SLOTS:
169  void updateQueueSize();
171  void fillTransportOptionList(EnumProperty* property);
172 
173  // Property callbacks
174  virtual void updateTopic();
175  virtual void updateTopicFilter();
176  virtual void updateUseAutoSize();
177  virtual void updateAutoSizeFactor();
178  virtual void updateUseOcclusionCompensation();
179  virtual void updateOcclusionTimeOut();
180 
181 protected:
182  void scanForTransportSubscriberPlugins();
183 
184  typedef std::vector<rviz::PointCloud::Point> V_Point;
185 
186  virtual void processMessage(const sensor_msgs::Image::ConstPtr& msg);
187  virtual void processMessage(const sensor_msgs::ImageConstPtr& depth_msg,
188  const sensor_msgs::ImageConstPtr& rgb_msg);
189  void caminfoCallback(sensor_msgs::CameraInfo::ConstPtr msg);
190 
191  // overrides from Display
192  void onEnable() override;
193  void onDisable() override;
194 
195  void fixedFrameChanged() override;
196 
197  void subscribe();
198  void unsubscribe();
199 
200  void clear();
201 
202  // thread-safe status updates
203  // add status update to global status list
204  void updateStatus(StatusProperty::Level level, const QString& name, const QString& text);
205 
206  // use global status list to update rviz plugin status
207  void setStatusList();
208 
210 
211  // ROS image subscription & synchronization
212  boost::scoped_ptr<image_transport::ImageTransport> depthmap_it_;
215  boost::scoped_ptr<image_transport::ImageTransport> rgb_it_;
218  sensor_msgs::CameraInfo::ConstPtr cam_info_;
219  boost::mutex cam_info_mutex_;
220 
223 
225 
226  // RVIZ properties
237 
238  uint32_t queue_size_;
239 
241 
242  Ogre::Quaternion current_orientation_;
243  Ogre::Vector3 current_position_;
246 
248 
249  std::set<std::string> transport_plugin_types_;
250 };
251 
252 
253 } // namespace rviz
254 
255 #endif // RVIZ_DEPTHMAP_TO_POINTCLOUD_DISPLAY_H
rviz::DepthCloudDisplay::rgb_sub_
boost::shared_ptr< image_transport::SubscriberFilter > rgb_sub_
Definition: depth_cloud_display.h:216
rviz::DepthCloudDisplay::pointcloud_common_
PointCloudCommon * pointcloud_common_
Definition: depth_cloud_display.h:247
rviz::DepthCloudDisplay::V_Point
std::vector< rviz::PointCloud::Point > V_Point
Definition: depth_cloud_display.h:184
unsubscribe
void unsubscribe()
rviz::RosTopicProperty
Definition: ros_topic_property.h:39
message_filters::Synchronizer
boost::shared_ptr< image_transport::SubscriberFilter >
ros_topic_property.h
rviz::DepthCloudDisplay::SyncPolicyDepthColor
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
Definition: depth_cloud_display.h:221
rviz::DepthCloudDisplay::topic_filter_property_
Property * topic_filter_property_
Definition: depth_cloud_display.h:227
ros.h
rviz::RosFilteredTopicProperty::filter_
QRegularExpression filter_
Definition: depth_cloud_display.h:146
rviz::StatusProperty::Level
Level
Definition: status_property.h:42
point_cloud_common.h
int_property.h
rviz::BoolProperty
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
description
description
rviz::DepthCloudDisplay::depthmap_it_
boost::scoped_ptr< image_transport::ImageTransport > depthmap_it_
Definition: depth_cloud_display.h:212
rviz::DepthCloudDisplay::queue_size_property_
IntProperty * queue_size_property_
Definition: depth_cloud_display.h:228
float_property.h
rviz::DepthCloudDisplay::sync_depth_color_
boost::shared_ptr< SynchronizerDepthColor > sync_depth_color_
Definition: depth_cloud_display.h:224
rviz::DepthCloudDisplay::rgb_it_
boost::scoped_ptr< image_transport::ImageTransport > rgb_it_
Definition: depth_cloud_display.h:215
bool_property.h
rviz::DepthCloudDisplay
Definition: depth_cloud_display.h:154
rviz::MultiLayerDepth
Definition: depth_cloud_mld.h:66
rviz::Display
Definition: display.h:63
rviz::EnumProperty
Enum property.
Definition: enum_property.h:46
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::DepthCloudDisplay::ml_depth_data_
MultiLayerDepth * ml_depth_data_
Definition: depth_cloud_display.h:240
rviz::Property
A single element of a property tree, with a name, value, description, and possibly children.
Definition: property.h:100
message_filters::sync_policies::ApproximateTime
rviz::DepthCloudDisplay::angular_thres_
float angular_thres_
Definition: depth_cloud_display.h:244
subscriber_filter.h
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
message_filter.h
rviz::DepthCloudDisplay::depth_topic_property_
RosFilteredTopicProperty * depth_topic_property_
Definition: depth_cloud_display.h:231
rviz::DepthCloudDisplay::use_auto_size_property_
BoolProperty * use_auto_size_property_
Definition: depth_cloud_display.h:229
rviz
Definition: add_display_dialog.cpp:54
subscriber.h
rviz::RosFilteredTopicProperty::filter_enabled_
bool filter_enabled_
Definition: depth_cloud_display.h:147
rviz::DepthCloudDisplay::current_position_
Ogre::Vector3 current_position_
Definition: depth_cloud_display.h:243
subscribe
void subscribe()
rviz::DepthCloudDisplay::depth_transport_property_
EnumProperty * depth_transport_property_
Definition: depth_cloud_display.h:232
rviz::DepthCloudDisplay::SynchronizerDepthColor
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
Definition: depth_cloud_display.h:222
rviz::DepthCloudDisplay::color_transport_property_
EnumProperty * color_transport_property_
Definition: depth_cloud_display.h:234
rviz::PointCloudCommon
Displays a point cloud of type sensor_msgs::PointCloud.
Definition: point_cloud_common.h:84
rviz::DepthCloudDisplay::use_occlusion_compensation_property_
BoolProperty * use_occlusion_compensation_property_
Definition: depth_cloud_display.h:235
rviz::DepthCloudDisplay::cam_info_sub_
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::CameraInfo > > cam_info_sub_
Definition: depth_cloud_display.h:217
rviz::RosFilteredTopicProperty::fillTopicList
void fillTopicList() override
Definition: depth_cloud_display.h:134
image_transport.h
rviz::DepthCloudDisplay::transport_plugin_types_
std::set< std::string > transport_plugin_types_
Definition: depth_cloud_display.h:249
rviz::DepthCloudDisplay::current_orientation_
Ogre::Quaternion current_orientation_
Definition: depth_cloud_display.h:242
rviz::RosFilteredTopicProperty
Definition: depth_cloud_display.h:77
rviz::DepthCloudDisplay::depthmap_sub_
boost::shared_ptr< image_transport::SubscriberFilter > depthmap_sub_
Definition: depth_cloud_display.h:213
message_filters::sync_policies
display.h
rviz::RosFilteredTopicProperty::RosFilteredTopicProperty
RosFilteredTopicProperty(const QString &name, const QString &default_value, const QString &message_type, const QString &description, const QRegularExpression &filter, Property *parent, Func &&changed_slot, const R *receiver)
Definition: depth_cloud_display.h:94
rviz::RosFilteredTopicProperty::RosFilteredTopicProperty
RosFilteredTopicProperty(const QString &name=QString(), const QString &default_value=QString(), const QString &message_type=QString(), const QString &description=QString(), const QRegularExpression &filter=QRegularExpression(), Property *parent=nullptr)
Definition: depth_cloud_display.h:81
rviz::RosFilteredTopicProperty::enableFilter
void enableFilter(bool enabled)
Definition: depth_cloud_display.h:122
rviz::RosFilteredTopicProperty::RosFilteredTopicProperty
RosFilteredTopicProperty(const QString &name, const QString &default_value, const QString &message_type, const QString &description, const QRegularExpression &filter, P *parent, Func &&changed_slot)
Definition: depth_cloud_display.h:109
rviz::DepthCloudDisplay::cam_info_mutex_
boost::mutex cam_info_mutex_
Definition: depth_cloud_display.h:219
rviz::DepthCloudDisplay::depthmap_tf_filter_
boost::shared_ptr< tf2_ros::MessageFilter< sensor_msgs::Image > > depthmap_tf_filter_
Definition: depth_cloud_display.h:214
rviz::RosFilteredTopicProperty::filter
QRegularExpression filter() const
Definition: depth_cloud_display.h:128
default_value
def default_value(type_)
datatype
const char * datatype()
image_transport
synchronizer.h
approximate_time.h
rviz::DepthCloudDisplay::trans_thres_
float trans_thres_
Definition: depth_cloud_display.h:245
rviz::DepthCloudDisplay::cam_info_
sensor_msgs::CameraInfo::ConstPtr cam_info_
Definition: depth_cloud_display.h:218
rviz::DepthCloudDisplay::messages_received_
uint32_t messages_received_
Definition: depth_cloud_display.h:209
rviz::DepthCloudDisplay::queue_size_
uint32_t queue_size_
Definition: depth_cloud_display.h:238
rviz::DepthCloudDisplay::color_topic_property_
RosFilteredTopicProperty * color_topic_property_
Definition: depth_cloud_display.h:233
rviz::DepthCloudDisplay::occlusion_shadow_timeout_property_
FloatProperty * occlusion_shadow_timeout_property_
Definition: depth_cloud_display.h:236
rviz::DepthCloudDisplay::auto_size_factor_property_
FloatProperty * auto_size_factor_property_
Definition: depth_cloud_display.h:230
enum_property.h
rviz::IntProperty
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:37


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:52