depth_cloud_display.cpp
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 #include <QObject>
30 #include <QRegularExpression>
31 
32 #include "depth_cloud_display.h"
35 #include <rviz/validate_floats.h>
36 
41 #include <rviz/frame_manager.h>
42 
43 #include <tf2_ros/buffer.h>
44 
45 #include <boost/bind/bind.hpp>
46 #include <boost/algorithm/string/erase.hpp>
47 #include <boost/foreach.hpp>
48 #include <boost/shared_ptr.hpp>
49 
50 #include <OgreSceneNode.h>
51 #include <OgreSceneManager.h>
52 
56 
58 
59 #include "depth_cloud_mld.h"
60 
61 #include <sstream>
62 #include <string>
63 #include <math.h>
64 
66 
67 namespace rviz
68 {
70  : rviz::Display()
71  , messages_received_(0)
72  , depthmap_sub_()
73  , rgb_sub_()
74  , cam_info_sub_()
75  , queue_size_(5)
76  , ml_depth_data_(new MultiLayerDepth())
77  , angular_thres_(0.5f)
78  , trans_thres_(0.01f)
79 
80 {
81  // Depth map properties
82  QRegularExpression depth_filter("depth", QRegularExpression::CaseInsensitiveOption);
83 
85  new Property("Topic Filter", true,
86  "List only topics with names that relate to depth and color images", this,
88 
90  "Depth Map Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()),
91  "sensor_msgs::Image topic to subscribe to.", depth_filter, this, &DepthCloudDisplay::updateTopic);
92 
94  new EnumProperty("Depth Map Transport Hint", "raw", "Preferred method of sending images.", this,
96 
99 
101 
102  // color image properties
103  QRegularExpression color_filter("color|rgb|bgr|gray|mono", QRegularExpression::CaseInsensitiveOption);
104 
106  "Color Image Topic", "",
107  QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()),
108  "sensor_msgs::Image topic to subscribe to.", color_filter, this, &DepthCloudDisplay::updateTopic);
109 
111  new EnumProperty("Color Transport Hint", "raw", "Preferred method of sending images.", this,
113 
114 
117 
119 
120  // Queue size property
122  new IntProperty("Queue Size", queue_size_,
123  "Advanced: set the size of the incoming message queue. Increasing this "
124  "is useful if your incoming TF data is delayed significantly from your"
125  " image data, but it can greatly increase memory usage if the messages are big.",
128 
130  "Auto Size", true,
131  "Automatically scale each point based on its depth value and the camera parameters.", this,
133 
135  new FloatProperty("Auto Size Factor", 1, "Scaling factor to be applied to the auto size.",
138 
140  new BoolProperty("Occlusion Compensation", false,
141  "Keep points alive after they have been occluded by a closer point. Points are "
142  "removed after a timeout or when the camera frame moves.",
144 
146  new FloatProperty("Occlusion Time-Out", 30.0f,
147  "Amount of seconds before removing occluded points from the depth cloud",
149  this);
150 }
151 
153 {
156 
157  // Instantiate PointCloudCommon class for displaying point clouds
159 
162 
163  // Scan for available transport plugins
165 
168 }
169 
171 {
172  if (initialized())
173  {
174  unsubscribe();
175  delete pointcloud_common_;
176  }
177 
178  if (ml_depth_data_)
179  {
180  delete ml_depth_data_;
181  }
182 }
183 
184 void DepthCloudDisplay::setTopic(const QString& topic, const QString& datatype)
185 {
186  // Copied from ImageDisplayBase::setTopic()
187  if (datatype == ros::message_traits::datatype<sensor_msgs::Image>())
188  {
191  }
192  else
193  {
194  int index = topic.lastIndexOf("/");
195  if (index == -1)
196  {
197  ROS_WARN("DepthCloudDisplay::setTopic() Invalid topic name: %s", topic.toStdString().c_str());
198  return;
199  }
200  QString transport = topic.mid(index + 1);
201  QString base_topic = topic.mid(0, index);
202 
204  depth_topic_property_->setString(base_topic);
205  }
206 }
207 
209 {
211 }
212 
214 {
215  bool use_auto_size = use_auto_size_property_->getBool();
217  pointcloud_common_->setAutoSize(use_auto_size);
218  auto_size_factor_property_->setHidden(!use_auto_size);
219  if (use_auto_size)
221 }
222 
224 {
225 }
226 
228 {
229  bool enabled = topic_filter_property_->getValue().toBool();
232 }
233 
235 {
236  bool use_occlusion_compensation = use_occlusion_compensation_property_->getBool();
237  occlusion_shadow_timeout_property_->setHidden(!use_occlusion_compensation);
238 
239  if (use_occlusion_compensation)
240  {
244  }
245  else
246  {
248  }
249 }
250 
252 {
253  float occlusion_timeout = occlusion_shadow_timeout_property_->getFloat();
254  ml_depth_data_->setShadowTimeOut(occlusion_timeout);
255 }
256 
258 {
259  subscribe();
260 }
261 
263 {
264  unsubscribe();
265 
267 
268  clear();
269 }
270 
272 {
273  if (!isEnabled())
274  {
275  return;
276  }
277 
278  try
279  {
280  // reset all message filters
282  depthmap_tf_filter_.reset();
286 
287  std::string depthmap_topic = depth_topic_property_->getTopicStd();
288  std::string color_topic = color_topic_property_->getTopicStd();
289 
290  std::string depthmap_transport = depth_transport_property_->getStdString();
291  std::string color_transport = color_transport_property_->getStdString();
292 
293  if (!depthmap_topic.empty() && !depthmap_transport.empty())
294  {
295  // subscribe to depth map topic
296  depthmap_sub_->subscribe(*depthmap_it_, depthmap_topic, queue_size_,
297  image_transport::TransportHints(depthmap_transport));
298 
301  threaded_nh_));
302 
303  // subscribe to CameraInfo topic
304  std::string info_topic = image_transport::getCameraInfoTopic(depthmap_topic);
305  cam_info_sub_->subscribe(threaded_nh_, info_topic, queue_size_);
306  cam_info_sub_->registerCallback(
307  boost::bind(&DepthCloudDisplay::caminfoCallback, this, boost::placeholders::_1));
308 
309  if (!color_topic.empty() && !color_transport.empty())
310  {
311  // subscribe to color image topic
312  rgb_sub_->subscribe(*rgb_it_, color_topic, queue_size_,
313  image_transport::TransportHints(color_transport));
314 
315  // connect message filters to synchronizer
317  sync_depth_color_->setInterMessageLowerBound(0, ros::Duration(0.5));
318  sync_depth_color_->setInterMessageLowerBound(1, ros::Duration(0.5));
319  sync_depth_color_->registerCallback(boost::bind(
320  &DepthCloudDisplay::processMessage, this, boost::placeholders::_1, boost::placeholders::_2));
321 
323  }
324  else
325  {
326  depthmap_tf_filter_->registerCallback(
327  boost::bind(&DepthCloudDisplay::processMessage, this, boost::placeholders::_1));
328  }
329  }
330  }
331  catch (ros::Exception& e)
332  {
333  setStatus(StatusProperty::Error, "Message", QString("Error subscribing: ") + e.what());
334  }
336  {
337  setStatus(StatusProperty::Error, "Message", QString("Error subscribing: ") + e.what());
338  }
339 }
340 
341 void DepthCloudDisplay::caminfoCallback(sensor_msgs::CameraInfo::ConstPtr msg)
342 {
343  boost::mutex::scoped_lock lock(cam_info_mutex_);
344  cam_info_ = std::move(msg);
345 }
346 
348 {
349  clear();
350 
351  try
352  {
353  // reset all filters
355  depthmap_tf_filter_.reset();
356  depthmap_sub_.reset();
357  rgb_sub_.reset();
358  cam_info_sub_.reset();
359  }
360  catch (ros::Exception& e)
361  {
362  setStatus(StatusProperty::Error, "Message", QString("Error unsubscribing: ") + e.what());
363  }
364 }
365 
366 
368 {
370 }
371 
372 
373 void DepthCloudDisplay::update(float wall_dt, float ros_dt)
374 {
375  pointcloud_common_->update(wall_dt, ros_dt);
376 }
377 
378 
380 {
381  clear();
382  messages_received_ = 0;
383  setStatus(StatusProperty::Ok, "Depth Map", "0 depth maps received");
384  setStatus(StatusProperty::Ok, "Message", "Ok");
385 }
386 
387 void DepthCloudDisplay::processMessage(const sensor_msgs::ImageConstPtr& depth_msg)
388 {
389  processMessage(depth_msg, sensor_msgs::ImageConstPtr());
390 }
391 
392 void DepthCloudDisplay::processMessage(const sensor_msgs::ImageConstPtr& depth_msg,
393  const sensor_msgs::ImageConstPtr& rgb_msg)
394 {
396  {
397  return;
398  }
399 
400  std::ostringstream s;
401 
403  setStatus(StatusProperty::Ok, "Depth Map",
404  QString::number(messages_received_) + " depth maps received");
405  setStatus(StatusProperty::Ok, "Message", "Ok");
406 
407  sensor_msgs::CameraInfo::ConstPtr cam_info;
408  {
409  boost::mutex::scoped_lock lock(cam_info_mutex_);
410  cam_info = cam_info_;
411  }
412 
413  if (!cam_info || !depth_msg)
414  {
415  return;
416  }
417 
418  s.str("");
419  s << depth_msg->width << " x " << depth_msg->height;
420  setStatusStd(StatusProperty::Ok, "Depth Image Size", s.str());
421 
422  if (rgb_msg)
423  {
424  s.str("");
425  s << rgb_msg->width << " x " << rgb_msg->height;
426  setStatusStd(StatusProperty::Ok, "Image Size", s.str());
427 
428  if (depth_msg->header.frame_id != rgb_msg->header.frame_id)
429  {
430  std::stringstream errorMsg;
431  errorMsg << "Depth image frame id [" << depth_msg->header.frame_id.c_str()
432  << "] doesn't match color image frame id [" << rgb_msg->header.frame_id.c_str() << "]";
433  setStatusStd(StatusProperty::Warn, "Message", errorMsg.str());
434  }
435  }
436 
438  {
439  float f = cam_info->K[0];
440  float bx = cam_info->binning_x > 0 ? cam_info->binning_x : 1.0;
443  }
444 
445  bool use_occlusion_compensation = use_occlusion_compensation_property_->getBool();
446 
447  if (use_occlusion_compensation)
448  {
449  // reset depth cloud display if camera moves
450  Ogre::Quaternion orientation;
451  Ogre::Vector3 position;
452 
453  if (!context_->getFrameManager()->getTransform(depth_msg->header, position, orientation))
454  {
455  setStatus(StatusProperty::Error, "Message",
456  QString("Failed to transform from frame [") + depth_msg->header.frame_id.c_str() +
457  QString("] to frame [") + context_->getFrameManager()->getFixedFrame().c_str() +
458  QString("]"));
459  return;
460  }
461  else
462  {
463  Ogre::Radian angle;
464  Ogre::Vector3 axis;
465 
466  (current_orientation_.Inverse() * orientation).ToAngleAxis(angle, axis);
467 
468  float angle_deg = angle.valueDegrees();
469  if (angle_deg >= 180.0f)
470  angle_deg -= 180.0f;
471  if (angle_deg < -180.0f)
472  angle_deg += 180.0f;
473 
474  if (trans_thres_ == 0.0 || angular_thres_ == 0.0 ||
475  (position - current_position_).length() > trans_thres_ || angle_deg > angular_thres_)
476  {
477  // camera orientation/position changed
478  current_position_ = position;
479  current_orientation_ = orientation;
480 
481  // reset multi-layered depth image
483  }
484  }
485  }
486 
487  try
488  {
489  sensor_msgs::PointCloud2Ptr cloud_msg =
490  ml_depth_data_->generatePointCloudFromDepth(depth_msg, rgb_msg, cam_info);
491 
492  if (!cloud_msg.get())
493  {
494  throw MultiLayerDepthException("generatePointCloudFromDepth() returned zero.");
495  }
496  cloud_msg->header = depth_msg->header;
497 
498  // add point cloud message to pointcloud_common to be visualized
499  pointcloud_common_->addMessage(cloud_msg);
500  }
501  catch (MultiLayerDepthException& e)
502  {
503  setStatus(StatusProperty::Error, "Message", QString("Error updating depth cloud: ") + e.what());
504  }
505 }
506 
507 
509 {
511  "image_transport", "image_transport::SubscriberPlugin");
512 
513  BOOST_FOREACH (const std::string& lookup_name, sub_loader.getDeclaredClasses())
514  {
515  // lookup_name is formatted as "pkg/transport_sub", for instance
516  // "image_transport/compressed_sub" for the "compressed"
517  // transport. This code removes the "_sub" from the tail and
518  // everything up to and including the "/" from the head, leaving
519  // "compressed" (for example) in transport_name.
520  std::string transport_name = boost::erase_last_copy(lookup_name, "_sub");
521  transport_name = transport_name.substr(lookup_name.find('/') + 1);
522 
523  // If the plugin loads without throwing an exception, add its
524  // transport name to the list of valid plugins, otherwise ignore
525  // it.
526  try
527  {
529  transport_plugin_types_.insert(transport_name);
530  }
531  catch (const pluginlib::LibraryLoadException& e)
532  {
533  }
534  catch (const pluginlib::CreateClassException& e)
535  {
536  }
537  }
538 }
539 
541 {
542  unsubscribe();
543  reset();
544  subscribe();
546 }
547 
549 {
550  property->clearOptions();
551 
552  std::vector<std::string> choices;
553 
554  choices.push_back("raw");
555 
556  // Loop over all current ROS topic names
558  ros::master::getTopics(topics);
559  ros::master::V_TopicInfo::iterator it = topics.begin();
560  ros::master::V_TopicInfo::iterator end = topics.end();
561  for (; it != end; ++it)
562  {
563  // If the beginning of this topic name is the same as topic_,
564  // and the whole string is not the same,
565  // and the next character is /
566  // and there are no further slashes from there to the end,
567  // then consider this a possible transport topic.
568  const ros::master::TopicInfo& ti = *it;
569  const std::string& topic_name = ti.name;
570  const std::string& topic = depth_topic_property_->getStdString();
571 
572  if (topic_name.find(topic) == 0 && topic_name != topic && topic_name[topic.size()] == '/' &&
573  topic_name.find('/', topic.size() + 1) == std::string::npos)
574  {
575  std::string transport_type = topic_name.substr(topic.size() + 1);
576 
577  // If the transport type string found above is in the set of
578  // supported transport type plugins, add it to the list.
579  if (transport_plugin_types_.find(transport_type) != transport_plugin_types_.end())
580  {
581  choices.push_back(transport_type);
582  }
583  }
584  }
585 
586  for (size_t i = 0; i < choices.size(); i++)
587  {
588  property->addOptionStd(choices[i]);
589  }
590 }
591 
593 {
594  Display::reset();
595 }
596 
597 } // namespace rviz
598 
600 #include <utility>
601 
602 
rviz::DepthCloudDisplay::rgb_sub_
boost::shared_ptr< image_transport::SubscriberFilter > rgb_sub_
Definition: depth_cloud_display.h:216
rviz::BoolProperty::getBool
virtual bool getBool() const
Definition: bool_property.cpp:48
image_transport::SubscriberFilter
sensor_msgs::image_encodings
rviz::DepthCloudDisplay::pointcloud_common_
PointCloudCommon * pointcloud_common_
Definition: depth_cloud_display.h:247
rviz::Display::isEnabled
bool isEnabled() const
Return true if this Display is enabled, false if not.
Definition: display.cpp:271
rviz::IntProperty::setMin
void setMin(int min)
Definition: int_property.cpp:52
image_transport::getCameraInfoTopic
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string &base_topic)
rviz::PointCloudCommon::setAutoSize
void setAutoSize(bool auto_size)
Definition: point_cloud_common.cpp:425
rviz::MultiLayerDepth::generatePointCloudFromDepth
sensor_msgs::PointCloud2Ptr generatePointCloudFromDepth(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg, sensor_msgs::CameraInfoConstPtr camera_info_msg)
Definition: depth_cloud_mld.cpp:454
validate_floats.h
rviz::DepthCloudDisplay::fixedFrameChanged
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
Definition: depth_cloud_display.cpp:592
frame_manager.h
rviz::Property::setHidden
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
Definition: property.cpp:566
pluginlib::CreateClassException
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
image_encodings.h
tf2_ros::MessageFilter
image_transport::ImageTransport
rviz::PointCloudCommon::xyz_transformer_property_
EnumProperty * xyz_transformer_property_
Definition: point_cloud_common.h:141
boost::shared_ptr< image_transport::SubscriberPlugin >
rviz::PointCloudCommon::initialize
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
Definition: point_cloud_common.cpp:366
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
rviz::Display::initialized
bool initialized() const
Returns true if the display has been initialized.
Definition: display.h:275
rviz::StatusProperty::Error
@ Error
Definition: status_property.h:46
rviz::EnumProperty::setString
virtual void setString(const QString &str)
Set the value of this property to the given string. Does not force the value to be one of the list of...
Definition: enum_property.cpp:82
rviz::DepthCloudDisplay::onEnable
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
Definition: depth_cloud_display.cpp:257
rviz::DepthCloudDisplay::updateUseOcclusionCompensation
virtual void updateUseOcclusionCompensation()
Definition: depth_cloud_display.cpp:234
rviz::PointCloudCommon::update
void update(float wall_dt, float ros_dt)
Definition: point_cloud_common.cpp:520
rviz::DepthCloudDisplay::SyncPolicyDepthColor
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
Definition: depth_cloud_display.h:221
s
XmlRpcServer s
rviz::DepthCloudDisplay::topic_filter_property_
Property * topic_filter_property_
Definition: depth_cloud_display.h:227
property.h
depth_cloud_mld.h
int_property.h
rviz::EditableEnumProperty::setString
virtual void setString(const QString &str)
Definition: editable_enum_property.cpp:74
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
buffer.h
rviz::EnumProperty::requestOptions
void requestOptions(EnumProperty *property_in_need_of_options)
requestOptions() is emitted each time createEditor() is called.
rviz::PointCloudCommon::addMessage
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
Definition: point_cloud_common.cpp:939
float_property.h
rviz::DepthCloudDisplay::sync_depth_color_
boost::shared_ptr< SynchronizerDepthColor > sync_depth_color_
Definition: depth_cloud_display.h:224
ros::Exception
rviz::Display::fixed_frame_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
rviz::DepthCloudDisplay::rgb_it_
boost::scoped_ptr< image_transport::ImageTransport > rgb_it_
Definition: depth_cloud_display.h:215
rviz::MultiLayerDepthException::what
const char * what() const override
Definition: depth_cloud_mld.h:57
bool_property.h
rviz::Property::getValue
virtual QVariant getValue() const
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant...
Definition: property.cpp:150
ros::master::getTopics
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
rviz::PointCloudCommon::point_world_size_property_
FloatProperty * point_world_size_property_
Definition: point_cloud_common.h:138
rviz::Property::Property
Property(const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr)
Constructor.
Definition: property.cpp:59
rviz::BoolProperty::BoolProperty
BoolProperty(const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr)
Definition: bool_property.cpp:36
rviz::FloatProperty::setMin
void setMin(float min)
Definition: float_property.cpp:51
rviz::DepthCloudDisplay
Definition: depth_cloud_display.h:154
f
f
message_filters::Subscriber< sensor_msgs::CameraInfo >
rviz::Property::connect
QMetaObject::Connection connect(const QObject *receiver, const char *slot, Qt::ConnectionType type=Qt::AutoConnection)
Connect changed() signal to given slot of receiver.
Definition: property.cpp:78
rviz::MultiLayerDepth
Definition: depth_cloud_mld.h:66
rviz::DepthCloudDisplay::updateTopicFilter
virtual void updateTopicFilter()
Definition: depth_cloud_display.cpp:227
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
image_transport::TransportLoadException
rviz::DepthCloudDisplay::setTopic
void setTopic(const QString &topic, const QString &datatype) override
Set the ROS topic to listen to for this display.
Definition: depth_cloud_display.cpp:184
rviz::Property::hide
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:462
rviz::Display::setStatus
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:176
rviz::MultiLayerDepth::enableOcclusionCompensation
void enableOcclusionCompensation(bool occlusion_compensation)
Definition: depth_cloud_mld.h:79
rviz::DepthCloudDisplay::fillTransportOptionList
void fillTransportOptionList(EnumProperty *property)
Fill list of available and working transport options.
Definition: depth_cloud_display.cpp:548
rviz::DepthCloudDisplay::DepthCloudDisplay
DepthCloudDisplay()
Definition: depth_cloud_display.cpp:69
rviz::DepthCloudDisplay::subscribe
void subscribe()
Definition: depth_cloud_display.cpp:271
rviz::DepthCloudDisplay::angular_thres_
float angular_thres_
Definition: depth_cloud_display.h:244
rviz::FrameManager::getFixedFrame
const std::string & getFixedFrame()
Return the current fixed frame name.
Definition: frame_manager.h:204
rviz::DepthCloudDisplay::unsubscribe
void unsubscribe()
Definition: depth_cloud_display.cpp:347
rviz::DepthCloudDisplay::onInitialize
void onInitialize() override
Override this function to do subclass-specific initialization.
Definition: depth_cloud_display.cpp:152
rviz::MultiLayerDepth::reset
void reset()
Definition: depth_cloud_mld.h:89
rviz::DepthCloudDisplay::updateOcclusionTimeOut
virtual void updateOcclusionTimeOut()
Definition: depth_cloud_display.cpp:251
rviz::DepthCloudDisplay::updateTopic
virtual void updateTopic()
Definition: depth_cloud_display.cpp:540
rviz::DepthCloudDisplay::updateQueueSize
void updateQueueSize()
Definition: depth_cloud_display.cpp:208
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
subscriber_filter.h
rviz::FloatProperty::getFloat
virtual float getFloat() const
Definition: float_property.h:79
rviz::Property::expand
virtual void expand()
Expand (show the children of) this Property.
Definition: property.cpp:578
rviz::DepthCloudDisplay::depth_topic_property_
RosFilteredTopicProperty * depth_topic_property_
Definition: depth_cloud_display.h:231
rviz::MultiLayerDepthException
Definition: depth_cloud_mld.h:47
rviz::Property::setValue
virtual bool setValue(const QVariant &new_value)
Set the new value for this property. Returns true if the new value is different from the old value,...
Definition: property.cpp:134
rviz::DepthCloudDisplay::use_auto_size_property_
BoolProperty * use_auto_size_property_
Definition: depth_cloud_display.h:229
rviz
Definition: add_display_dialog.cpp:54
ros::master::V_TopicInfo
std::vector< TopicInfo > V_TopicInfo
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
rviz::DepthCloudDisplay::current_position_
Ogre::Vector3 current_position_
Definition: depth_cloud_display.h:243
rviz::StringProperty::getStdString
std::string getStdString()
Definition: string_property.h:71
rviz::StatusProperty::Ok
@ Ok
Definition: status_property.h:44
rviz::StatusProperty::Warn
@ Warn
Definition: status_property.h:45
rviz::DepthCloudDisplay::scanForTransportSubscriberPlugins
void scanForTransportSubscriberPlugins()
Definition: depth_cloud_display.cpp:508
rviz::DepthCloudDisplay::clear
void clear()
Definition: depth_cloud_display.cpp:367
rviz::FrameManager::getPause
bool getPause()
Definition: frame_manager.h:97
rviz::DepthCloudDisplay::caminfoCallback
void caminfoCallback(sensor_msgs::CameraInfo::ConstPtr msg)
Definition: depth_cloud_display.cpp:341
rviz::DepthCloudDisplay::onDisable
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
Definition: depth_cloud_display.cpp:262
ROS_WARN
#define ROS_WARN(...)
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
pluginlib::ClassLoader
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::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
subscriber_plugin.h
rviz::RosTopicProperty::getTopicStd
std::string getTopicStd() const
Definition: ros_topic_property.h:85
depth_cloud_display.h
visualization_manager.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
camera_common.h
rviz::DepthCloudDisplay::processMessage
virtual void processMessage(const sensor_msgs::Image::ConstPtr &msg)
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
Definition: frame_manager.h:125
rviz::Display::setStatusStd
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
Show status level and text, using a std::string. Convenience function which converts std::string to Q...
Definition: display.h:163
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Definition: display.h:287
rviz::PointCloudCommon::color_transformer_property_
EnumProperty * color_transformer_property_
Definition: point_cloud_common.h:142
pluginlib::ClassLoader::createInstance
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
rviz::FloatProperty::setFloat
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
Definition: float_property.h:97
rviz::Property::setReadOnly
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
Definition: property.h:497
rviz::RosFilteredTopicProperty::enableFilter
void enableFilter(bool enabled)
Definition: depth_cloud_display.h:122
rviz::DepthCloudDisplay::cam_info_mutex_
boost::mutex cam_info_mutex_
Definition: depth_cloud_display.h:219
rviz::DepthCloudDisplay::~DepthCloudDisplay
~DepthCloudDisplay() override
Definition: depth_cloud_display.cpp:170
rviz::DepthCloudDisplay::depthmap_tf_filter_
boost::shared_ptr< tf2_ros::MessageFilter< sensor_msgs::Image > > depthmap_tf_filter_
Definition: depth_cloud_display.h:214
rviz::StringProperty::setStdString
bool setStdString(const std::string &std_str)
Definition: string_property.h:85
class_list_macros.hpp
datatype
const char * datatype()
rviz::MultiLayerDepth::setShadowTimeOut
void setShadowTimeOut(double time_out)
Definition: depth_cloud_mld.h:74
rviz::Display::reset
virtual void reset()
Called to tell the display to clear its state.
Definition: display.cpp:290
rviz::IntProperty::getInt
virtual int getInt() const
Return the internal property value as an integer.
Definition: int_property.h:96
pluginlib::LibraryLoadException
rviz::PointCloudCommon::reset
void reset()
Definition: point_cloud_common.cpp:508
rviz::DepthCloudDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: depth_cloud_display.cpp:379
rviz::Display::threaded_nh_
ros::NodeHandle threaded_nh_
A NodeHandle whose CallbackQueue is run from a different thread than the GUI.
Definition: display.h:305
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
image_transport::TransportHints
rviz::DepthCloudDisplay::update
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Definition: depth_cloud_display.cpp:373
rviz::DepthCloudDisplay::color_topic_property_
RosFilteredTopicProperty * color_topic_property_
Definition: depth_cloud_display.h:233
ros::master::TopicInfo
ros::Duration
rviz::DepthCloudDisplay::updateUseAutoSize
virtual void updateUseAutoSize()
Definition: depth_cloud_display.cpp:213
rviz::DisplayContext::getTF2BufferPtr
std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const
Convenience function: returns getFrameManager()->getTF2BufferPtr().
Definition: display_context.h:98
rviz::DepthCloudDisplay::occlusion_shadow_timeout_property_
FloatProperty * occlusion_shadow_timeout_property_
Definition: depth_cloud_display.h:236
rviz::DepthCloudDisplay::updateAutoSizeFactor
virtual void updateAutoSizeFactor()
Definition: depth_cloud_display.cpp:223
rviz::DepthCloudDisplay::auto_size_factor_property_
FloatProperty * auto_size_factor_property_
Definition: depth_cloud_display.h:230
ros::master::TopicInfo::name
std::string name
enum_property.h
rviz::IntProperty
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:37
pluginlib::ClassLoader::getDeclaredClasses
std::vector< std::string > getDeclaredClasses()


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