Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Private Types | Friends
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  PluginConns
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 createProperties ()
virtual void fixedFrameChanged ()
float getAlpha ()
float getBillboardSize ()
float getDecayTime ()
bool getSelectable ()
int getStyle ()
 PointCloudBase (const std::string &name, VisualizationManager *manager)
virtual void reset ()
void setAlpha (float alpha)
void setBillboardSize (float size)
 Sets the size each point will be when drawn in 3D as a billboard.
void setDecayTime (float time)
 Set the amount of time each cloud should stick around for.
void setSelectable (bool selectable)
void setStyle (int style)
 Set the rendering style.
virtual void update (float wall_dt, float ros_dt)
 ~PointCloudBase ()

Protected Types

typedef std::map< Plugin
*, PluginConns
M_PluginConns
typedef std::map< std::string,
TransformerInfo
M_TransformerInfo
typedef std::vector
< ogre_tools::PointCloud::Point
V_Point
typedef std::vector< V_PointVV_Point

Protected Member Functions

void addMessage (const sensor_msgs::PointCloudConstPtr &cloud)
void addMessage (const sensor_msgs::PointCloud2ConstPtr &cloud)
const std::string & getColorTransformer ()
PointCloudTransformerPtr getColorTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud)
const std::string & getXYZTransformer ()
PointCloudTransformerPtr getXYZTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud)
void loadTransformers (Plugin *plugin)
virtual void onDisable ()
virtual void onEnable ()
void onPluginLoaded (const PluginStatus &status)
void onPluginUnloading (const PluginStatus &status)
void onTransformerOptions (V_string &ops, uint32_t mask)
void processMessage (const sensor_msgs::PointCloud2ConstPtr &cloud)
void retransform ()
void setColorTransformer (const std::string &name)
void setXYZTransformer (const std::string &name)
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, bool fully_update)

Protected Attributes

float alpha_
FloatPropertyWPtr alpha_property_
float billboard_size_
 Size to draw our billboards.
FloatPropertyWPtr billboard_size_property_
ros::CallbackQueue cbqueue_
ogre_tools::PointCloudcloud_
D_CloudInfo clouds_
boost::mutex clouds_mutex_
CollObjectHandle coll_handle_
PointCloudSelectionHandlerPtr coll_handler_
std::string color_transformer_
EditEnumPropertyWPtr color_transformer_property_
FloatPropertyWPtr decay_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_
M_PluginConns plugin_conns_
float point_decay_time_
 How long clouds should stick around for before they are culled.
Ogre::SceneNode * scene_node_
bool selectable_
BoolPropertyWPtr selectable_property_
ros::AsyncSpinner spinner_
int style_
 Our rendering style.
EnumPropertyWPtr style_property_
uint32_t total_point_count_
M_TransformerInfo transformers_
boost::recursive_mutex transformers_mutex_
std::string xyz_transformer_
EditEnumPropertyWPtr xyz_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

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 97 of file point_cloud_base.h.


Member Typedef Documentation

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

Definition at line 117 of file point_cloud_base.h.

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

Definition at line 118 of file point_cloud_base.h.

Definition at line 278 of file point_cloud_base.h.

Definition at line 244 of file point_cloud_base.h.

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

Definition at line 120 of file point_cloud_base.h.

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

Definition at line 119 of file point_cloud_base.h.

Definition at line 192 of file point_cloud_base.h.

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

Definition at line 193 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 141 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 127 of file point_cloud_base.h.


Constructor & Destructor Documentation

rviz::PointCloudBase::PointCloudBase ( const std::string &  name,
VisualizationManager manager 
)

Definition at line 365 of file point_cloud_base.cpp.

Definition at line 421 of file point_cloud_base.cpp.


Member Function Documentation

Definition at line 1157 of file point_cloud_base.cpp.

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

Definition at line 1164 of file point_cloud_base.cpp.

Definition at line 665 of file point_cloud_base.cpp.

Reimplemented in srs_env_model_ui::CButPointCloud.

Definition at line 1206 of file point_cloud_base.cpp.

Reimplemented from rviz::Display.

Reimplemented in srs_env_model_ui::CButPointCloud.

Definition at line 1176 of file point_cloud_base.cpp.

float rviz::PointCloudBase::getAlpha ( ) [inline]

Definition at line 174 of file point_cloud_base.h.

Definition at line 170 of file point_cloud_base.h.

const std::string& rviz::PointCloudBase::getColorTransformer ( ) [inline, protected]

Definition at line 208 of file point_cloud_base.h.

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

Definition at line 993 of file point_cloud_base.cpp.

Definition at line 172 of file point_cloud_base.h.

Definition at line 177 of file point_cloud_base.h.

Definition at line 171 of file point_cloud_base.h.

const std::string& rviz::PointCloudBase::getXYZTransformer ( ) [inline, protected]

Definition at line 207 of file point_cloud_base.h.

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

Definition at line 977 of file point_cloud_base.cpp.

void rviz::PointCloudBase::loadTransformers ( Plugin *  plugin) [protected]

Definition at line 521 of file point_cloud_base.cpp.

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

Reimplemented from rviz::Display.

Reimplemented in srs_env_model_ui::CButPointCloud.

Definition at line 657 of file point_cloud_base.cpp.

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

Reimplemented from rviz::Display.

Reimplemented in srs_env_model_ui::CButPointCloud.

Definition at line 653 of file point_cloud_base.cpp.

void rviz::PointCloudBase::onPluginLoaded ( const PluginStatus status) [protected]

Definition at line 455 of file point_cloud_base.cpp.

void rviz::PointCloudBase::onPluginUnloading ( const PluginStatus status) [protected]

Definition at line 460 of file point_cloud_base.cpp.

void rviz::PointCloudBase::onTransformerOptions ( V_string ops,
uint32_t  mask 
) [protected]

Definition at line 1181 of file point_cloud_base.cpp.

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

Definition at line 918 of file point_cloud_base.cpp.

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

Reimplemented from rviz::Display.

Definition at line 1271 of file point_cloud_base.cpp.

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

Definition at line 1009 of file point_cloud_base.cpp.

void rviz::PointCloudBase::setAlpha ( float  alpha)

Definition at line 556 of file point_cloud_base.cpp.

Sets the size each point will be when drawn in 3D as a billboard.

Note:
Only applicable if the style is set to Billboards (default)
Parameters:
sizeThe size

Definition at line 642 of file point_cloud_base.cpp.

void rviz::PointCloudBase::setColorTransformer ( const std::string &  name) [protected]

Definition at line 957 of file point_cloud_base.cpp.

void rviz::PointCloudBase::setDecayTime ( float  time)

Set the amount of time each cloud should stick around for.

Parameters:
timeDecay time, in seconds

Definition at line 597 of file point_cloud_base.cpp.

Definition at line 565 of file point_cloud_base.cpp.

void rviz::PointCloudBase::setStyle ( int  style)

Set the rendering style.

Parameters:
styleThe rendering style

Definition at line 606 of file point_cloud_base.cpp.

void rviz::PointCloudBase::setXYZTransformer ( const std::string &  name) [protected]

Definition at line 937 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 1036 of file point_cloud_base.cpp.

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

Reimplemented from rviz::Display.

Reimplemented in srs_env_model_ui::CButPointCloud.

Definition at line 671 of file point_cloud_base.cpp.

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

Definition at line 898 of file point_cloud_base.cpp.

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

Definition at line 798 of file point_cloud_base.cpp.


Friends And Related Function Documentation

friend class PointCloudSelectionHandler [friend]

Definition at line 281 of file point_cloud_base.h.


Member Data Documentation

float rviz::PointCloudBase::alpha_ [protected]

Definition at line 233 of file point_cloud_base.h.

FloatPropertyWPtr rviz::PointCloudBase::alpha_property_ [protected]

Definition at line 267 of file point_cloud_base.h.

Size to draw our billboards.

Definition at line 255 of file point_cloud_base.h.

FloatPropertyWPtr rviz::PointCloudBase::billboard_size_property_ [protected]

Definition at line 266 of file point_cloud_base.h.

Definition at line 220 of file point_cloud_base.h.

Definition at line 226 of file point_cloud_base.h.

Definition at line 222 of file point_cloud_base.h.

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

Definition at line 223 of file point_cloud_base.h.

Definition at line 259 of file point_cloud_base.h.

Definition at line 260 of file point_cloud_base.h.

Definition at line 249 of file point_cloud_base.h.

EditEnumPropertyWPtr rviz::PointCloudBase::color_transformer_property_ [protected]

Definition at line 269 of file point_cloud_base.h.

FloatPropertyWPtr rviz::PointCloudBase::decay_time_property_ [protected]

Definition at line 271 of file point_cloud_base.h.

Definition at line 262 of file point_cloud_base.h.

Definition at line 252 of file point_cloud_base.h.

Definition at line 224 of file point_cloud_base.h.

Definition at line 230 of file point_cloud_base.h.

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

Definition at line 231 of file point_cloud_base.h.

Definition at line 251 of file point_cloud_base.h.

Definition at line 229 of file point_cloud_base.h.

Definition at line 250 of file point_cloud_base.h.

Definition at line 279 of file point_cloud_base.h.

How long clouds should stick around for before they are culled.

Definition at line 256 of file point_cloud_base.h.

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

Reimplemented from rviz::Display.

Definition at line 227 of file point_cloud_base.h.

Definition at line 258 of file point_cloud_base.h.

BoolPropertyWPtr rviz::PointCloudBase::selectable_property_ [protected]

Definition at line 265 of file point_cloud_base.h.

Definition at line 219 of file point_cloud_base.h.

Our rendering style.

Definition at line 254 of file point_cloud_base.h.

EnumPropertyWPtr rviz::PointCloudBase::style_property_ [protected]

Definition at line 270 of file point_cloud_base.h.

Definition at line 263 of file point_cloud_base.h.

Definition at line 247 of file point_cloud_base.h.

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

Definition at line 246 of file point_cloud_base.h.

std::string rviz::PointCloudBase::xyz_transformer_ [protected]

Definition at line 248 of file point_cloud_base.h.

EditEnumPropertyWPtr rviz::PointCloudBase::xyz_transformer_property_ [protected]

Definition at line 268 of file point_cloud_base.h.


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


srs_env_model_ui
Author(s): Michal Spanel (spanel@fit.vutbr.cz), Vit Stancl (stancl@fit.vutbr.cz)
autogenerated on Mon Oct 6 2014 08:14:22