Public Member Functions | Protected Types | Protected Slots | Protected Member Functions | Protected Attributes
rviz::DepthCloudDisplay Class Reference

#include <depth_cloud_display.h>

Inheritance diagram for rviz::DepthCloudDisplay:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 DepthCloudDisplay ()
virtual void onInitialize ()
 Override this function to do subclass-specific initialization.
virtual void reset ()
 Called to tell the display to clear its state.
virtual void setTopic (const QString &topic, const QString &datatype)
 Set the ROS topic to listen to for this display.
virtual void update (float wall_dt, float ros_dt)
 Called periodically by the visualization manager.
virtual ~DepthCloudDisplay ()

Protected Types

typedef
message_filters::Synchronizer
< SyncPolicyDepthColor
SynchronizerDepthColor
typedef ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image > 
SyncPolicyDepthColor
typedef std::vector
< rviz::PointCloud::Point
V_Point

Protected Slots

void fillTransportOptionList (EnumProperty *property)
 Fill list of available and working transport options.
virtual void updateAutoSizeFactor ()
virtual void updateOcclusionTimeOut ()
void updateQueueSize ()
virtual void updateTopic ()
virtual void updateTopicFilter ()
virtual void updateUseAutoSize ()
virtual void updateUseOcclusionCompensation ()

Protected Member Functions

void caminfoCallback (sensor_msgs::CameraInfo::ConstPtr msg)
void clear ()
virtual void fixedFrameChanged ()
 Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
virtual void onDisable ()
 Derived classes override this to do the actual work of disabling themselves.
virtual void onEnable ()
 Derived classes override this to do the actual work of enabling themselves.
virtual void processMessage (sensor_msgs::Image::ConstPtr msg)
virtual void processMessage (sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImageConstPtr rgb_msg)
void scanForTransportSubscriberPlugins ()
void setStatusList ()
void subscribe ()
void unsubscribe ()
void updateStatus (StatusProperty::Level level, const QString &name, const QString &text)

Protected Attributes

float angular_thres_
FloatPropertyauto_size_factor_property_
sensor_msgs::CameraInfo::ConstPtr cam_info_
boost::mutex cam_info_mutex_
boost::shared_ptr
< message_filters::Subscriber
< sensor_msgs::CameraInfo > > 
cam_info_sub_
RosFilteredTopicPropertycolor_topic_property_
EnumPropertycolor_transport_property_
Ogre::Quaternion current_orientation_
Ogre::Vector3 current_position_
RosFilteredTopicPropertydepth_topic_property_
EnumPropertydepth_transport_property_
boost::scoped_ptr
< image_transport::ImageTransport
depthmap_it_
boost::shared_ptr
< image_transport::SubscriberFilter
depthmap_sub_
boost::shared_ptr
< tf::MessageFilter
< sensor_msgs::Image > > 
depthmap_tf_filter_
uint32_t messages_received_
MultiLayerDepthml_depth_data_
boost::mutex mutex_
FloatPropertyocclusion_shadow_timeout_property_
PointCloudCommonpointcloud_common_
u_int32_t queue_size_
IntPropertyqueue_size_property_
boost::scoped_ptr
< image_transport::ImageTransport
rgb_it_
boost::shared_ptr
< image_transport::SubscriberFilter
rgb_sub_
boost::shared_ptr
< SynchronizerDepthColor
sync_depth_color_
Propertytopic_filter_property_
float trans_thres_
std::set< std::string > transport_plugin_types_
BoolPropertyuse_auto_size_property_
BoolPropertyuse_occlusion_compensation_property_

Detailed Description

Definition at line 123 of file depth_cloud_display.h.


Member Typedef Documentation

Definition at line 192 of file depth_cloud_display.h.

typedef ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> rviz::DepthCloudDisplay::SyncPolicyDepthColor [protected]

Definition at line 191 of file depth_cloud_display.h.

Definition at line 153 of file depth_cloud_display.h.


Constructor & Destructor Documentation

Definition at line 69 of file depth_cloud_display.cpp.

Definition at line 186 of file depth_cloud_display.cpp.


Member Function Documentation

void rviz::DepthCloudDisplay::caminfoCallback ( sensor_msgs::CameraInfo::ConstPtr  msg) [protected]

Definition at line 349 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::clear ( ) [protected]

Definition at line 375 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::fillTransportOptionList ( EnumProperty property) [protected, slot]

Fill list of available and working transport options.

Definition at line 565 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::fixedFrameChanged ( ) [protected, virtual]

Called by setFixedFrame(). Override to respond to changes to fixed_frame_.

Reimplemented from rviz::Display.

Definition at line 609 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::onDisable ( ) [protected, virtual]

Derived classes override this to do the actual work of disabling themselves.

Reimplemented from rviz::Display.

Definition at line 278 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::onEnable ( ) [protected, virtual]

Derived classes override this to do the actual work of enabling themselves.

Reimplemented from rviz::Display.

Definition at line 273 of file depth_cloud_display.cpp.

Override this function to do subclass-specific initialization.

This is called after vis_manager_ and scene_manager_ are set, and before load() or setEnabled().

setName() may or may not have been called before this.

Reimplemented from rviz::Display.

Definition at line 164 of file depth_cloud_display.cpp.

virtual void rviz::DepthCloudDisplay::processMessage ( sensor_msgs::Image::ConstPtr  msg) [protected, virtual]
void rviz::DepthCloudDisplay::processMessage ( sensor_msgs::ImageConstPtr  depth_msg,
sensor_msgs::ImageConstPtr  rgb_msg 
) [protected, virtual]

Definition at line 406 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::reset ( ) [virtual]

Called to tell the display to clear its state.

Reimplemented from rviz::Display.

Definition at line 393 of file depth_cloud_display.cpp.

Definition at line 525 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::setTopic ( const QString &  topic,
const QString &  datatype 
) [virtual]

Set the ROS topic to listen to for this display.

By default, do nothing. Subclasses should override this method if they subscribe to a single ROS topic.

setTopic() is used by the "New display by topic" window; it is called with a user selected topic and its type.

Parameters:
topicThe published topic to be visualized.
datatypeThe datatype of the topic.

Reimplemented from rviz::Display.

Definition at line 200 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::subscribe ( ) [protected]

Definition at line 287 of file depth_cloud_display.cpp.

Definition at line 355 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Called periodically by the visualization manager.

Parameters:
wall_dtWall-clock time, in seconds, since the last time the update list was run through.
ros_dtROS time, in seconds, since the last time the update list was run through.

Reimplemented from rviz::Display.

Definition at line 384 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::updateAutoSizeFactor ( ) [protected, virtual, slot]

Definition at line 240 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::updateOcclusionTimeOut ( ) [protected, virtual, slot]

Definition at line 267 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::updateQueueSize ( ) [protected, slot]

Definition at line 225 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::updateStatus ( StatusProperty::Level  level,
const QString &  name,
const QString &  text 
) [protected]
void rviz::DepthCloudDisplay::updateTopic ( ) [protected, virtual, slot]

Definition at line 557 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::updateTopicFilter ( ) [protected, virtual, slot]

Definition at line 244 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::updateUseAutoSize ( ) [protected, virtual, slot]

Definition at line 230 of file depth_cloud_display.cpp.

void rviz::DepthCloudDisplay::updateUseOcclusionCompensation ( ) [protected, virtual, slot]

Definition at line 251 of file depth_cloud_display.cpp.


Member Data Documentation

Definition at line 214 of file depth_cloud_display.h.

Definition at line 200 of file depth_cloud_display.h.

sensor_msgs::CameraInfo::ConstPtr rviz::DepthCloudDisplay::cam_info_ [protected]

Definition at line 188 of file depth_cloud_display.h.

boost::mutex rviz::DepthCloudDisplay::cam_info_mutex_ [protected]

Definition at line 189 of file depth_cloud_display.h.

boost::shared_ptr<message_filters::Subscriber<sensor_msgs::CameraInfo> > rviz::DepthCloudDisplay::cam_info_sub_ [protected]

Definition at line 187 of file depth_cloud_display.h.

Definition at line 203 of file depth_cloud_display.h.

Definition at line 204 of file depth_cloud_display.h.

Ogre::Quaternion rviz::DepthCloudDisplay::current_orientation_ [protected]

Definition at line 212 of file depth_cloud_display.h.

Ogre::Vector3 rviz::DepthCloudDisplay::current_position_ [protected]

Definition at line 213 of file depth_cloud_display.h.

Definition at line 201 of file depth_cloud_display.h.

Definition at line 202 of file depth_cloud_display.h.

Definition at line 182 of file depth_cloud_display.h.

Definition at line 183 of file depth_cloud_display.h.

boost::shared_ptr<tf::MessageFilter<sensor_msgs::Image> > rviz::DepthCloudDisplay::depthmap_tf_filter_ [protected]

Definition at line 184 of file depth_cloud_display.h.

Definition at line 177 of file depth_cloud_display.h.

Definition at line 210 of file depth_cloud_display.h.

boost::mutex rviz::DepthCloudDisplay::mutex_ [protected]

Definition at line 179 of file depth_cloud_display.h.

Definition at line 206 of file depth_cloud_display.h.

Definition at line 217 of file depth_cloud_display.h.

u_int32_t rviz::DepthCloudDisplay::queue_size_ [protected]

Definition at line 208 of file depth_cloud_display.h.

Definition at line 198 of file depth_cloud_display.h.

Definition at line 185 of file depth_cloud_display.h.

Definition at line 186 of file depth_cloud_display.h.

Definition at line 194 of file depth_cloud_display.h.

Definition at line 197 of file depth_cloud_display.h.

Definition at line 215 of file depth_cloud_display.h.

Definition at line 219 of file depth_cloud_display.h.

Definition at line 199 of file depth_cloud_display.h.

Definition at line 205 of file depth_cloud_display.h.


The documentation for this class was generated from the following files:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:28