rviz::PointCloudBase Class Reference

Displays a point cloud of type sensor_msgs::PointCloud. More...

#include <point_cloud_base.h>

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

List of all members.

Classes

struct  CloudInfo
struct  TransformerInfo

Public Types

enum  ChannelRender {
  Intensity, Curvature, ColorRGBSpace, NormalSphere,
  ChannelRenderCount
}
 

The different channels that we support rendering.

More...
enum  Style {
  Points, Billboards, BillboardSpheres, Boxes,
  StyleCount
}
 

The different styles of pointcloud drawing.

More...

Public Member Functions

void causeRetransform ()
virtual void fixedFrameChanged ()
 Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void onInitialize ()
 Override this function to do subclass-specific initialization.
 PointCloudBase ()
virtual void reset ()
 Called to tell the display to clear its state.
virtual void update (float wall_dt, float ros_dt)
 Called periodically by the visualization manager.
 ~PointCloudBase ()

Protected Types

typedef std::map< std::string,
TransformerInfo
M_TransformerInfo
typedef std::vector
< PointCloud::Point
V_Point
typedef std::vector< V_PointVV_Point

Protected Member Functions

void addMessage (const sensor_msgs::PointCloud2ConstPtr &cloud)
void addMessage (const sensor_msgs::PointCloudConstPtr &cloud)
PointCloudTransformerPtr getColorTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud)
PointCloudTransformerPtr getXYZTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud)
void loadTransformers ()
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.
void onTransformerOptions (V_string &ops, uint32_t mask)
void processMessage (const sensor_msgs::PointCloud2ConstPtr &cloud)
void retransform ()
bool transformCloud (const CloudInfoPtr &cloud, V_Point &points, bool fully_update_transformers)
 Transforms the cloud into the correct frame, and sets up our renderable cloud.
void updateStatus ()
void updateTransformers (const sensor_msgs::PointCloud2ConstPtr &cloud)

Protected Attributes

FloatPropertyalpha_property_
FloatPropertybillboard_size_property_
ros::CallbackQueue cbqueue_
PointCloudcloud_
D_CloudInfo clouds_
boost::mutex clouds_mutex_
CollObjectHandle coll_handle_
PointCloudSelectionHandlerPtr coll_handler_
EnumPropertycolor_transformer_property_
FloatPropertydecay_time_property_
uint32_t messages_received_
bool needs_retransform_
bool new_cloud_
V_CloudInfo new_clouds_
boost::mutex new_clouds_mutex_
bool new_color_transformer_
VV_Point new_points_
bool new_xyz_transformer_
Ogre::SceneNode * scene_node_
BoolPropertyselectable_property_
ros::AsyncSpinner spinner_
EnumPropertystyle_property_
uint32_t total_point_count_
pluginlib::ClassLoader
< PointCloudTransformer > * 
transformer_class_loader_
M_TransformerInfo transformers_
boost::recursive_mutex transformers_mutex_
EnumPropertyxyz_transformer_property_

Private Types

typedef boost::shared_ptr
< CloudInfo
CloudInfoPtr
typedef std::deque< CloudInfoPtrD_CloudInfo
typedef std::queue< CloudInfoPtrQ_CloudInfo
typedef std::vector< CloudInfoPtrV_CloudInfo

Private Slots

void updateAlpha ()
void updateBillboardSize ()
void updateColorTransformer ()
void updateSelectable ()
void updateStyle ()
void updateXyzTransformer ()

Private Member Functions

float getSelectionBoxSize ()
void setPropertiesHidden (const QList< Property * > &props, bool hide)

Friends

class PointCloudSelectionHandler

Detailed Description

Displays a point cloud of type sensor_msgs::PointCloud.

By default it will assume channel 0 of the cloud is an intensity value, and will color them by intensity. If you set the channel's name to "rgb", it will interpret the channel as an integer rgb value, with r, g and b all being 8 bits.

Definition at line 76 of file point_cloud_base.h.


Member Typedef Documentation

typedef boost::shared_ptr<CloudInfo> rviz::PointCloudBase::CloudInfoPtr [private]

Definition at line 93 of file point_cloud_base.h.

typedef std::deque<CloudInfoPtr> rviz::PointCloudBase::D_CloudInfo [private]

Definition at line 94 of file point_cloud_base.h.

typedef std::map<std::string, TransformerInfo> rviz::PointCloudBase::M_TransformerInfo [protected]

Definition at line 196 of file point_cloud_base.h.

typedef std::queue<CloudInfoPtr> rviz::PointCloudBase::Q_CloudInfo [private]

Definition at line 96 of file point_cloud_base.h.

typedef std::vector<CloudInfoPtr> rviz::PointCloudBase::V_CloudInfo [private]

Definition at line 95 of file point_cloud_base.h.

typedef std::vector<PointCloud::Point> rviz::PointCloudBase::V_Point [protected]

Definition at line 152 of file point_cloud_base.h.

typedef std::vector<V_Point> rviz::PointCloudBase::VV_Point [protected]

Definition at line 153 of file point_cloud_base.h.


Member Enumeration Documentation

The different channels that we support rendering.

Enumerator:
Intensity 

Intensity data.

Curvature 

Surface curvature estimates.

ColorRGBSpace 

RGB Color.

NormalSphere 

Use the nx-ny-nz (normal coordinates) instead of x-y-z.

ChannelRenderCount 

Definition at line 117 of file point_cloud_base.h.

The different styles of pointcloud drawing.

Enumerator:
Points 

Points -- points are drawn as a fixed size in 2d space, ie. always 1 pixel on screen.

Billboards 

Billboards -- points are drawn as camera-facing quads in 3d space.

BillboardSpheres 

Billboard "spheres" -- cam-facing tris with a pixel shader that causes them to look like spheres.

Boxes 

Boxes -- Actual 3d cube geometry.

StyleCount 

Definition at line 103 of file point_cloud_base.h.


Constructor & Destructor Documentation

rviz::PointCloudBase::PointCloudBase (  ) 

Definition at line 342 of file point_cloud_base.cpp.

rviz::PointCloudBase::~PointCloudBase (  ) 

Definition at line 417 of file point_cloud_base.cpp.


Member Function Documentation

void rviz::PointCloudBase::addMessage ( const sensor_msgs::PointCloud2ConstPtr &  cloud  )  [protected]

Definition at line 958 of file point_cloud_base.cpp.

void rviz::PointCloudBase::addMessage ( const sensor_msgs::PointCloudConstPtr &  cloud  )  [protected]

Definition at line 951 of file point_cloud_base.cpp.

void rviz::PointCloudBase::causeRetransform (  ) 

Definition at line 529 of file point_cloud_base.cpp.

void rviz::PointCloudBase::fixedFrameChanged (  )  [virtual]

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

Reimplemented from rviz::Display.

Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.

Definition at line 970 of file point_cloud_base.cpp.

PointCloudTransformerPtr rviz::PointCloudBase::getColorTransformer ( const sensor_msgs::PointCloud2ConstPtr &  cloud  )  [protected]

Definition at line 791 of file point_cloud_base.cpp.

float rviz::PointCloudBase::getSelectionBoxSize (  )  [private]

Definition at line 1022 of file point_cloud_base.cpp.

PointCloudTransformerPtr rviz::PointCloudBase::getXYZTransformer ( const sensor_msgs::PointCloud2ConstPtr &  cloud  )  [protected]

Definition at line 775 of file point_cloud_base.cpp.

void rviz::PointCloudBase::loadTransformers (  )  [protected]

Definition at line 432 of file point_cloud_base.cpp.

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

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

Reimplemented from rviz::Display.

Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.

Definition at line 521 of file point_cloud_base.cpp.

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

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

Reimplemented from rviz::Display.

Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.

Definition at line 517 of file point_cloud_base.cpp.

void rviz::PointCloudBase::onInitialize (  )  [virtual]

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.

Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.

Definition at line 400 of file point_cloud_base.cpp.

void rviz::PointCloudBase::onTransformerOptions ( V_string ops,
uint32_t  mask 
) [protected]
void rviz::PointCloudBase::processMessage ( const sensor_msgs::PointCloud2ConstPtr &  cloud  )  [protected]

Definition at line 734 of file point_cloud_base.cpp.

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

Called to tell the display to clear its state.

Reimplemented from rviz::Display.

Definition at line 1012 of file point_cloud_base.cpp.

void rviz::PointCloudBase::retransform (  )  [protected]

Definition at line 807 of file point_cloud_base.cpp.

void rviz::PointCloudBase::setPropertiesHidden ( const QList< Property * > &  props,
bool  hide 
) [private]

Definition at line 648 of file point_cloud_base.cpp.

bool rviz::PointCloudBase::transformCloud ( const CloudInfoPtr cloud,
V_Point points,
bool  fully_update_transformers 
) [protected]

Transforms the cloud into the correct frame, and sets up our renderable cloud.

Definition at line 827 of file point_cloud_base.cpp.

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

Called periodically by the visualization manager.

Parameters:
wall_dt Wall-clock time, in seconds, since the last time the update list was run through.
ros_dt ROS time, in seconds, since the last time the update list was run through.

Reimplemented from rviz::Display.

Definition at line 535 of file point_cloud_base.cpp.

void rviz::PointCloudBase::updateAlpha (  )  [private, slot]

Definition at line 463 of file point_cloud_base.cpp.

void rviz::PointCloudBase::updateBillboardSize (  )  [private, slot]

Definition at line 510 of file point_cloud_base.cpp.

void rviz::PointCloudBase::updateColorTransformer (  )  [private, slot]

Definition at line 764 of file point_cloud_base.cpp.

void rviz::PointCloudBase::updateSelectable (  )  [private, slot]

Definition at line 468 of file point_cloud_base.cpp.

void rviz::PointCloudBase::updateStatus (  )  [protected]

Definition at line 714 of file point_cloud_base.cpp.

void rviz::PointCloudBase::updateStyle (  )  [private, slot]

Definition at line 495 of file point_cloud_base.cpp.

void rviz::PointCloudBase::updateTransformers ( const sensor_msgs::PointCloud2ConstPtr &  cloud  )  [protected]

Definition at line 656 of file point_cloud_base.cpp.

void rviz::PointCloudBase::updateXyzTransformer (  )  [private, slot]

Definition at line 753 of file point_cloud_base.cpp.


Friends And Related Function Documentation

friend class PointCloudSelectionHandler [friend]

Definition at line 220 of file point_cloud_base.h.


Member Data Documentation

Definition at line 214 of file point_cloud_base.h.

Definition at line 213 of file point_cloud_base.h.

ros::CallbackQueue rviz::PointCloudBase::cbqueue_ [protected]

Definition at line 174 of file point_cloud_base.h.

Definition at line 180 of file point_cloud_base.h.

Definition at line 176 of file point_cloud_base.h.

boost::mutex rviz::PointCloudBase::clouds_mutex_ [protected]

Definition at line 177 of file point_cloud_base.h.

Definition at line 204 of file point_cloud_base.h.

Definition at line 205 of file point_cloud_base.h.

Definition at line 216 of file point_cloud_base.h.

Definition at line 218 of file point_cloud_base.h.

Definition at line 207 of file point_cloud_base.h.

Definition at line 202 of file point_cloud_base.h.

Definition at line 178 of file point_cloud_base.h.

Definition at line 184 of file point_cloud_base.h.

boost::mutex rviz::PointCloudBase::new_clouds_mutex_ [protected]

Definition at line 185 of file point_cloud_base.h.

Definition at line 201 of file point_cloud_base.h.

Definition at line 183 of file point_cloud_base.h.

Definition at line 200 of file point_cloud_base.h.

Ogre::SceneNode* rviz::PointCloudBase::scene_node_ [protected]

Definition at line 181 of file point_cloud_base.h.

Definition at line 212 of file point_cloud_base.h.

ros::AsyncSpinner rviz::PointCloudBase::spinner_ [protected]

Definition at line 173 of file point_cloud_base.h.

Definition at line 217 of file point_cloud_base.h.

Definition at line 208 of file point_cloud_base.h.

Definition at line 210 of file point_cloud_base.h.

Definition at line 199 of file point_cloud_base.h.

boost::recursive_mutex rviz::PointCloudBase::transformers_mutex_ [protected]

Definition at line 198 of file point_cloud_base.h.

Definition at line 215 of file point_cloud_base.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Wed Jun 6 11:25:48 2012