Classes | Public Types | Public Slots | Public Member Functions | Public Attributes | Private Types | Private Slots | Private Member Functions | Private Attributes | Friends | List of all members
rviz::PointCloudCommon Class Reference

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

#include <point_cloud_common.h>

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

Classes

struct  CloudInfo
 
struct  TransformerInfo
 

Public Types

typedef boost::shared_ptr< CloudInfoCloudInfoPtr
 
typedef std::deque< CloudInfoPtrD_CloudInfo
 
typedef std::list< CloudInfoPtrL_CloudInfo
 
typedef std::queue< CloudInfoPtrQ_CloudInfo
 
typedef std::vector< CloudInfoPtrV_CloudInfo
 

Public Slots

void causeRetransform ()
 

Public Member Functions

void addMessage (const sensor_msgs::PointCloudConstPtr &cloud)
 
void addMessage (const sensor_msgs::PointCloud2ConstPtr &cloud)
 
void fixedFrameChanged ()
 
DisplaygetDisplay ()
 
void initialize (DisplayContext *context, Ogre::SceneNode *scene_node)
 
 PointCloudCommon (Display *display)
 
void reset ()
 
void setAutoSize (bool auto_size)
 
void update (float wall_dt, float ros_dt)
 
 ~PointCloudCommon () override
 

Public Attributes

FloatPropertyalpha_property_
 
bool auto_size_
 
EnumPropertycolor_transformer_property_
 
FloatPropertydecay_time_property_
 
FloatPropertypoint_pixel_size_property_
 
FloatPropertypoint_world_size_property_
 
BoolPropertyselectable_property_
 
EnumPropertystyle_property_
 
EnumPropertyxyz_transformer_property_
 

Private Types

typedef std::map< std::string, TransformerInfoM_TransformerInfo
 

Private Slots

void setColorTransformerOptions (EnumProperty *prop)
 
void setXyzTransformerOptions (EnumProperty *prop)
 
void updateAlpha ()
 
void updateBillboardSize ()
 
void updateColorTransformer ()
 
void updateSelectable ()
 
void updateStyle ()
 
void updateXyzTransformer ()
 

Private Member Functions

void fillTransformerOptions (EnumProperty *prop, uint32_t mask)
 
PointCloudTransformerPtr getColorTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud)
 
float getSelectionBoxSize ()
 
PointCloudTransformerPtr getXYZTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud)
 
void loadTransformers ()
 
void onTransformerOptions (V_string &ops, uint32_t mask)
 
void processMessage (const sensor_msgs::PointCloud2ConstPtr &cloud)
 
void retransform ()
 
void setPropertiesHidden (const QList< Property *> &props, bool hide)
 
bool transformCloud (const CloudInfoPtr &cloud, bool fully_update_transformers)
 Transforms the cloud into the correct frame, and sets up our renderable cloud. More...
 
void updateStatus ()
 
void updateTransformers (const sensor_msgs::PointCloud2ConstPtr &cloud)
 

Private Attributes

D_CloudInfo cloud_infos_
 
DisplayContextcontext_
 
Displaydisplay_
 
bool needs_retransform_
 
V_CloudInfo new_cloud_infos_
 
boost::mutex new_clouds_mutex_
 
bool new_color_transformer_
 
bool new_xyz_transformer_
 
L_CloudInfo obsolete_cloud_infos_
 
Ogre::SceneNode * scene_node_
 
pluginlib::ClassLoader< PointCloudTransformer > * transformer_class_loader_
 
M_TransformerInfo transformers_
 
boost::recursive_mutex transformers_mutex_
 

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 84 of file point_cloud_common.h.

Member Typedef Documentation

◆ CloudInfoPtr

Definition at line 112 of file point_cloud_common.h.

◆ D_CloudInfo

Definition at line 113 of file point_cloud_common.h.

◆ L_CloudInfo

Definition at line 116 of file point_cloud_common.h.

◆ M_TransformerInfo

typedef std::map<std::string, TransformerInfo> rviz::PointCloudCommon::M_TransformerInfo
private

Definition at line 200 of file point_cloud_common.h.

◆ Q_CloudInfo

Definition at line 115 of file point_cloud_common.h.

◆ V_CloudInfo

Definition at line 114 of file point_cloud_common.h.

Constructor & Destructor Documentation

◆ PointCloudCommon()

rviz::PointCloudCommon::PointCloudCommon ( Display display)

Definition at line 308 of file point_cloud_common.cpp.

◆ ~PointCloudCommon()

rviz::PointCloudCommon::~PointCloudCommon ( )
override

Definition at line 381 of file point_cloud_common.cpp.

Member Function Documentation

◆ addMessage() [1/2]

void rviz::PointCloudCommon::addMessage ( const sensor_msgs::PointCloudConstPtr &  cloud)

Definition at line 938 of file point_cloud_common.cpp.

◆ addMessage() [2/2]

void rviz::PointCloudCommon::addMessage ( const sensor_msgs::PointCloud2ConstPtr &  cloud)

Definition at line 945 of file point_cloud_common.cpp.

◆ causeRetransform

void rviz::PointCloudCommon::causeRetransform ( )
slot

Definition at line 514 of file point_cloud_common.cpp.

◆ fillTransformerOptions()

void rviz::PointCloudCommon::fillTransformerOptions ( EnumProperty prop,
uint32_t  mask 
)
private

Definition at line 965 of file point_cloud_common.cpp.

◆ fixedFrameChanged()

void rviz::PointCloudCommon::fixedFrameChanged ( )

Definition at line 950 of file point_cloud_common.cpp.

◆ getColorTransformer()

PointCloudTransformerPtr rviz::PointCloudCommon::getColorTransformer ( const sensor_msgs::PointCloud2ConstPtr &  cloud)
private

Definition at line 785 of file point_cloud_common.cpp.

◆ getDisplay()

Display* rviz::PointCloudCommon::getDisplay ( )
inline

Definition at line 130 of file point_cloud_common.h.

◆ getSelectionBoxSize()

float rviz::PointCloudCommon::getSelectionBoxSize ( )
private

Definition at line 990 of file point_cloud_common.cpp.

◆ getXYZTransformer()

PointCloudTransformerPtr rviz::PointCloudCommon::getXYZTransformer ( const sensor_msgs::PointCloud2ConstPtr &  cloud)
private

Definition at line 768 of file point_cloud_common.cpp.

◆ initialize()

void rviz::PointCloudCommon::initialize ( DisplayContext context,
Ogre::SceneNode *  scene_node 
)

Definition at line 366 of file point_cloud_common.cpp.

◆ loadTransformers()

void rviz::PointCloudCommon::loadTransformers ( )
private

Definition at line 389 of file point_cloud_common.cpp.

◆ onTransformerOptions()

void rviz::PointCloudCommon::onTransformerOptions ( V_string ops,
uint32_t  mask 
)
private

◆ processMessage()

void rviz::PointCloudCommon::processMessage ( const sensor_msgs::PointCloud2ConstPtr &  cloud)
private

Definition at line 731 of file point_cloud_common.cpp.

◆ reset()

void rviz::PointCloudCommon::reset ( )

Definition at line 507 of file point_cloud_common.cpp.

◆ retransform()

void rviz::PointCloudCommon::retransform ( )
private

Definition at line 802 of file point_cloud_common.cpp.

◆ setAutoSize()

void rviz::PointCloudCommon::setAutoSize ( bool  auto_size)

Definition at line 424 of file point_cloud_common.cpp.

◆ setColorTransformerOptions

void rviz::PointCloudCommon::setColorTransformerOptions ( EnumProperty prop)
privateslot

Definition at line 960 of file point_cloud_common.cpp.

◆ setPropertiesHidden()

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

Definition at line 646 of file point_cloud_common.cpp.

◆ setXyzTransformerOptions

void rviz::PointCloudCommon::setXyzTransformerOptions ( EnumProperty prop)
privateslot

Definition at line 955 of file point_cloud_common.cpp.

◆ transformCloud()

bool rviz::PointCloudCommon::transformCloud ( const CloudInfoPtr cloud,
bool  fully_update_transformers 
)
private

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

Definition at line 818 of file point_cloud_common.cpp.

◆ update()

void rviz::PointCloudCommon::update ( float  wall_dt,
float  ros_dt 
)

Definition at line 519 of file point_cloud_common.cpp.

◆ updateAlpha

void rviz::PointCloudCommon::updateAlpha ( )
privateslot

Definition at line 434 of file point_cloud_common.cpp.

◆ updateBillboardSize

void rviz::PointCloudCommon::updateBillboardSize ( )
privateslot

Definition at line 487 of file point_cloud_common.cpp.

◆ updateColorTransformer

void rviz::PointCloudCommon::updateColorTransformer ( )
privateslot

Definition at line 756 of file point_cloud_common.cpp.

◆ updateSelectable

void rviz::PointCloudCommon::updateSelectable ( )
privateslot

Definition at line 443 of file point_cloud_common.cpp.

◆ updateStatus()

void rviz::PointCloudCommon::updateStatus ( )
private

Definition at line 724 of file point_cloud_common.cpp.

◆ updateStyle

void rviz::PointCloudCommon::updateStyle ( )
privateslot

Definition at line 467 of file point_cloud_common.cpp.

◆ updateTransformers()

void rviz::PointCloudCommon::updateTransformers ( const sensor_msgs::PointCloud2ConstPtr &  cloud)
private

Definition at line 654 of file point_cloud_common.cpp.

◆ updateXyzTransformer

void rviz::PointCloudCommon::updateXyzTransformer ( )
privateslot

Definition at line 745 of file point_cloud_common.cpp.

Friends And Related Function Documentation

◆ PointCloudSelectionHandler

friend class PointCloudSelectionHandler
friend

Definition at line 213 of file point_cloud_common.h.

Member Data Documentation

◆ alpha_property_

FloatProperty* rviz::PointCloudCommon::alpha_property_

Definition at line 140 of file point_cloud_common.h.

◆ auto_size_

bool rviz::PointCloudCommon::auto_size_

Definition at line 135 of file point_cloud_common.h.

◆ cloud_infos_

D_CloudInfo rviz::PointCloudCommon::cloud_infos_
private

Definition at line 182 of file point_cloud_common.h.

◆ color_transformer_property_

EnumProperty* rviz::PointCloudCommon::color_transformer_property_

Definition at line 142 of file point_cloud_common.h.

◆ context_

DisplayContext* rviz::PointCloudCommon::context_
private

Definition at line 211 of file point_cloud_common.h.

◆ decay_time_property_

FloatProperty* rviz::PointCloudCommon::decay_time_property_

Definition at line 144 of file point_cloud_common.h.

◆ display_

Display* rviz::PointCloudCommon::display_
private

Definition at line 210 of file point_cloud_common.h.

◆ needs_retransform_

bool rviz::PointCloudCommon::needs_retransform_
private

Definition at line 206 of file point_cloud_common.h.

◆ new_cloud_infos_

V_CloudInfo rviz::PointCloudCommon::new_cloud_infos_
private

Definition at line 186 of file point_cloud_common.h.

◆ new_clouds_mutex_

boost::mutex rviz::PointCloudCommon::new_clouds_mutex_
private

Definition at line 187 of file point_cloud_common.h.

◆ new_color_transformer_

bool rviz::PointCloudCommon::new_color_transformer_
private

Definition at line 205 of file point_cloud_common.h.

◆ new_xyz_transformer_

bool rviz::PointCloudCommon::new_xyz_transformer_
private

Definition at line 204 of file point_cloud_common.h.

◆ obsolete_cloud_infos_

L_CloudInfo rviz::PointCloudCommon::obsolete_cloud_infos_
private

Definition at line 189 of file point_cloud_common.h.

◆ point_pixel_size_property_

FloatProperty* rviz::PointCloudCommon::point_pixel_size_property_

Definition at line 139 of file point_cloud_common.h.

◆ point_world_size_property_

FloatProperty* rviz::PointCloudCommon::point_world_size_property_

Definition at line 138 of file point_cloud_common.h.

◆ scene_node_

Ogre::SceneNode* rviz::PointCloudCommon::scene_node_
private

Definition at line 184 of file point_cloud_common.h.

◆ selectable_property_

BoolProperty* rviz::PointCloudCommon::selectable_property_

Definition at line 137 of file point_cloud_common.h.

◆ style_property_

EnumProperty* rviz::PointCloudCommon::style_property_

Definition at line 143 of file point_cloud_common.h.

◆ transformer_class_loader_

pluginlib::ClassLoader<PointCloudTransformer>* rviz::PointCloudCommon::transformer_class_loader_
private

Definition at line 208 of file point_cloud_common.h.

◆ transformers_

M_TransformerInfo rviz::PointCloudCommon::transformers_
private

Definition at line 203 of file point_cloud_common.h.

◆ transformers_mutex_

boost::recursive_mutex rviz::PointCloudCommon::transformers_mutex_
private

Definition at line 202 of file point_cloud_common.h.

◆ xyz_transformer_property_

EnumProperty* rviz::PointCloudCommon::xyz_transformer_property_

Definition at line 141 of file point_cloud_common.h.


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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:26