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 ()
 
ros::CallbackQueueInterfacegetCallbackQueue ()
 
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 ()
 

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

ros::CallbackQueue cbqueue_
 
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_
 
ros::AsyncSpinner spinner_
 
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 85 of file point_cloud_common.h.

Member Typedef Documentation

Definition at line 113 of file point_cloud_common.h.

Definition at line 114 of file point_cloud_common.h.

Definition at line 117 of file point_cloud_common.h.

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

Definition at line 204 of file point_cloud_common.h.

Definition at line 116 of file point_cloud_common.h.

Definition at line 115 of file point_cloud_common.h.

Constructor & Destructor Documentation

rviz::PointCloudCommon::PointCloudCommon ( Display display)

Definition at line 314 of file point_cloud_common.cpp.

rviz::PointCloudCommon::~PointCloudCommon ( )

Definition at line 386 of file point_cloud_common.cpp.

Member Function Documentation

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

Definition at line 918 of file point_cloud_common.cpp.

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

Definition at line 925 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::causeRetransform ( )
slot

Definition at line 517 of file point_cloud_common.cpp.

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

Definition at line 945 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::fixedFrameChanged ( )

Definition at line 930 of file point_cloud_common.cpp.

ros::CallbackQueueInterface* rviz::PointCloudCommon::getCallbackQueue ( )
inline

Definition at line 131 of file point_cloud_common.h.

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

Definition at line 777 of file point_cloud_common.cpp.

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

Definition at line 133 of file point_cloud_common.h.

float rviz::PointCloudCommon::getSelectionBoxSize ( )
private

Definition at line 970 of file point_cloud_common.cpp.

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

Definition at line 761 of file point_cloud_common.cpp.

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

Definition at line 370 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::loadTransformers ( )
private

Definition at line 396 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::onTransformerOptions ( V_string ops,
uint32_t  mask 
)
private
void rviz::PointCloudCommon::processMessage ( const sensor_msgs::PointCloud2ConstPtr &  cloud)
private

Definition at line 725 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::reset ( )

Definition at line 510 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::retransform ( )
private

Definition at line 794 of file point_cloud_common.cpp.

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

Definition at line 431 of file point_cloud_common.cpp.

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

Definition at line 940 of file point_cloud_common.cpp.

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

Definition at line 641 of file point_cloud_common.cpp.

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

Definition at line 935 of file point_cloud_common.cpp.

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 809 of file point_cloud_common.cpp.

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

Definition at line 522 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::updateAlpha ( )
privateslot

Definition at line 442 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::updateBillboardSize ( )
privateslot

Definition at line 493 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::updateColorTransformer ( )
privateslot

Definition at line 750 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::updateSelectable ( )
privateslot

Definition at line 451 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::updateStatus ( )
private

Definition at line 718 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::updateStyle ( )
privateslot

Definition at line 473 of file point_cloud_common.cpp.

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

Definition at line 649 of file point_cloud_common.cpp.

void rviz::PointCloudCommon::updateXyzTransformer ( )
privateslot

Definition at line 739 of file point_cloud_common.cpp.

Friends And Related Function Documentation

friend class PointCloudSelectionHandler
friend

Definition at line 217 of file point_cloud_common.h.

Member Data Documentation

FloatProperty* rviz::PointCloudCommon::alpha_property_

Definition at line 140 of file point_cloud_common.h.

bool rviz::PointCloudCommon::auto_size_

Definition at line 135 of file point_cloud_common.h.

ros::CallbackQueue rviz::PointCloudCommon::cbqueue_
private

Definition at line 184 of file point_cloud_common.h.

D_CloudInfo rviz::PointCloudCommon::cloud_infos_
private

Definition at line 186 of file point_cloud_common.h.

EnumProperty* rviz::PointCloudCommon::color_transformer_property_

Definition at line 142 of file point_cloud_common.h.

DisplayContext* rviz::PointCloudCommon::context_
private

Definition at line 215 of file point_cloud_common.h.

FloatProperty* rviz::PointCloudCommon::decay_time_property_

Definition at line 144 of file point_cloud_common.h.

Display* rviz::PointCloudCommon::display_
private

Definition at line 214 of file point_cloud_common.h.

bool rviz::PointCloudCommon::needs_retransform_
private

Definition at line 210 of file point_cloud_common.h.

V_CloudInfo rviz::PointCloudCommon::new_cloud_infos_
private

Definition at line 190 of file point_cloud_common.h.

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

Definition at line 191 of file point_cloud_common.h.

bool rviz::PointCloudCommon::new_color_transformer_
private

Definition at line 209 of file point_cloud_common.h.

bool rviz::PointCloudCommon::new_xyz_transformer_
private

Definition at line 208 of file point_cloud_common.h.

L_CloudInfo rviz::PointCloudCommon::obsolete_cloud_infos_
private

Definition at line 193 of file point_cloud_common.h.

FloatProperty* rviz::PointCloudCommon::point_pixel_size_property_

Definition at line 139 of file point_cloud_common.h.

FloatProperty* rviz::PointCloudCommon::point_world_size_property_

Definition at line 138 of file point_cloud_common.h.

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

Definition at line 188 of file point_cloud_common.h.

BoolProperty* rviz::PointCloudCommon::selectable_property_

Definition at line 137 of file point_cloud_common.h.

ros::AsyncSpinner rviz::PointCloudCommon::spinner_
private

Definition at line 183 of file point_cloud_common.h.

EnumProperty* rviz::PointCloudCommon::style_property_

Definition at line 143 of file point_cloud_common.h.

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

Definition at line 212 of file point_cloud_common.h.

M_TransformerInfo rviz::PointCloudCommon::transformers_
private

Definition at line 207 of file point_cloud_common.h.

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

Definition at line 206 of file point_cloud_common.h.

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 Wed Aug 28 2019 04:01:53