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