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 <tf/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 
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 QRegExp& filter = QRegExp(),
86  Property* parent = 0,
87  const char *changed_slot = 0,
88  QObject* receiver = 0) :
89  RosTopicProperty(name, default_value, message_type, description, parent, changed_slot, receiver), filter_(filter), filter_enabled_(true)
90  {
91 
92  }
93 
94  public:
95  void enableFilter (bool enabled)
96  {
97  filter_enabled_ = enabled;
98  fillTopicList();
99  }
100 
101  QRegExp filter() const { return filter_; }
102 
103 protected Q_SLOTS:
104  virtual void fillTopicList()
105  {
106  QStringList filtered_strings_;
107 
108  // Obtain list of available topics
109  RosTopicProperty::fillTopicList();
110  // Apply filter
111  if (filter_enabled_)
112  strings_ = strings_.filter(filter_);
113  }
114 private:
115  QRegExp filter_;
117 };
118 
124 {
125 Q_OBJECT
126 public:
128  virtual ~DepthCloudDisplay();
129 
130  virtual void onInitialize();
131 
132  // Overrides from Display
133  virtual void update(float wall_dt, float ros_dt);
134  virtual void reset();
135  virtual void setTopic( const QString &topic, const QString &datatype );
136 
137 protected Q_SLOTS:
138  void updateQueueSize();
140  void fillTransportOptionList(EnumProperty* property);
141 
142  // Property callbacks
143  virtual void updateTopic();
144  virtual void updateTopicFilter();
145  virtual void updateUseAutoSize();
146  virtual void updateAutoSizeFactor();
147  virtual void updateUseOcclusionCompensation();
148  virtual void updateOcclusionTimeOut();
149 
150 protected:
151  void scanForTransportSubscriberPlugins();
152 
153  typedef std::vector<rviz::PointCloud::Point> V_Point;
154 
155  virtual void processMessage(sensor_msgs::Image::ConstPtr msg);
156  virtual void processMessage(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImageConstPtr rgb_msg);
157  void caminfoCallback( sensor_msgs::CameraInfo::ConstPtr msg );
158 
159  // overrides from Display
160  virtual void onEnable();
161  virtual void onDisable();
162 
163  virtual void fixedFrameChanged();
164 
165  void subscribe();
166  void unsubscribe();
167 
168  void clear();
169 
170  // thread-safe status updates
171  // add status update to global status list
172  void updateStatus( StatusProperty::Level level, const QString& name, const QString& text );
173 
174  // use global status list to update rviz plugin status
175  void setStatusList( );
176 
178 
179  boost::mutex mutex_;
180 
181  // ROS image subscription & synchronization
182  boost::scoped_ptr<image_transport::ImageTransport> depthmap_it_;
185  boost::scoped_ptr<image_transport::ImageTransport> rgb_it_;
188  sensor_msgs::CameraInfo::ConstPtr cam_info_;
189  boost::mutex cam_info_mutex_;
190 
193 
195 
196  // RVIZ properties
207 
208  u_int32_t queue_size_;
209 
211 
212  Ogre::Quaternion current_orientation_;
213  Ogre::Vector3 current_position_;
216 
218 
219  std::set<std::string> transport_plugin_types_;
220 
221 };
222 
223 
224 } // namespace rviz
225 
226 #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_
boost::shared_ptr< image_transport::SubscriberFilter > rgb_sub_
std::vector< rviz::PointCloud::Point > V_Point
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=0, const char *changed_slot=0, QObject *receiver=0)
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_
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:38
boost::shared_ptr< image_transport::SubscriberFilter > depthmap_sub_
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()
description
boost::scoped_ptr< image_transport::ImageTransport > depthmap_it_
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::CameraInfo > > cam_info_sub_
def default_value(type)
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_
Enum property.
Definition: enum_property.h:47
BoolProperty * use_auto_size_property_
boost::shared_ptr< tf::MessageFilter< sensor_msgs::Image > > depthmap_tf_filter_
RosFilteredTopicProperty * depth_topic_property_


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:50