rviz::IntensityPCTransformer Class Reference

#include <point_cloud_transformers.h>

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

List of all members.

Public Member Functions

virtual void createProperties (PropertyManager *property_man, const CategoryPropertyWPtr &parent, const std::string &prefix, uint32_t mask, V_PropertyBaseWPtr &out_props)
 Create any properties necessary for this transformer. Will be called once when the transformer is loaded. All properties must be added to the out_props vector.
bool getAutoComputeIntensityBounds ()
const ColorgetMaxColor ()
float getMaxIntensity ()
const ColorgetMinColor ()
float getMinIntensity ()
 IntensityPCTransformer ()
virtual void reset ()
 Reset any internal state used by this transformer.
virtual uint8_t score (const sensor_msgs::PointCloud2ConstPtr &cloud)
 "Score" a message for how well supported the message is. For example, a "flat color" transformer can support any cloud, but will return a score of 0 here since it should not be preferred over others that explicitly support fields in the message. This allows that "flat color" transformer to still be selectable, but generally not chosen automatically.
void setAutoComputeIntensityBounds (bool compute)
void setMaxColor (const Color &color)
void setMaxIntensity (float val)
void setMinColor (const Color &color)
void setMinIntensity (float val)
virtual uint8_t supports (const sensor_msgs::PointCloud2ConstPtr &cloud)
 Returns a level of support for a specific cloud. This level of support is a mask using the SupportLevel enum.
virtual bool transform (const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, PointCloud &out)
 Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preallocated into the correct size. The mask determines which part of the cloud should be output (xyz or color). This method will only be called if supports() of the same cloud has returned a non-zero mask, and will only be called with masks compatible with the one returned from supports().

Private Attributes

bool auto_compute_intensity_bounds_
BoolPropertyWPtr auto_compute_intensity_bounds_property_
bool intensity_bounds_changed_
Color max_color_
ColorPropertyWPtr max_color_property_
float max_intensity_
FloatPropertyWPtr max_intensity_property_
Color min_color_
ColorPropertyWPtr min_color_property_
float min_intensity_
FloatPropertyWPtr min_intensity_property_
RetransformFunc retransform_func_

Detailed Description

Definition at line 105 of file point_cloud_transformers.h.


Constructor & Destructor Documentation

rviz::IntensityPCTransformer::IntensityPCTransformer (  )  [inline]

Definition at line 108 of file point_cloud_transformers.h.


Member Function Documentation

void rviz::IntensityPCTransformer::createProperties ( PropertyManager property_man,
const CategoryPropertyWPtr &  parent,
const std::string &  prefix,
uint32_t  mask,
V_PropertyBaseWPtr out_props 
) [virtual]

Create any properties necessary for this transformer. Will be called once when the transformer is loaded. All properties must be added to the out_props vector.

Reimplemented from rviz::PointCloudTransformer.

Definition at line 141 of file point_cloud_transformers.cpp.

bool rviz::IntensityPCTransformer::getAutoComputeIntensityBounds (  )  [inline]

Definition at line 132 of file point_cloud_transformers.h.

const Color& rviz::IntensityPCTransformer::getMaxColor (  )  [inline]

Definition at line 125 of file point_cloud_transformers.h.

float rviz::IntensityPCTransformer::getMaxIntensity (  )  [inline]

Definition at line 130 of file point_cloud_transformers.h.

const Color& rviz::IntensityPCTransformer::getMinColor (  )  [inline]

Definition at line 126 of file point_cloud_transformers.h.

float rviz::IntensityPCTransformer::getMinIntensity (  )  [inline]

Definition at line 129 of file point_cloud_transformers.h.

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

Reset any internal state used by this transformer.

Reimplemented from rviz::PointCloudTransformer.

Definition at line 135 of file point_cloud_transformers.cpp.

uint8_t rviz::IntensityPCTransformer::score ( const sensor_msgs::PointCloud2ConstPtr &  cloud  )  [virtual]

"Score" a message for how well supported the message is. For example, a "flat color" transformer can support any cloud, but will return a score of 0 here since it should not be preferred over others that explicitly support fields in the message. This allows that "flat color" transformer to still be selectable, but generally not chosen automatically.

Reimplemented from rviz::PointCloudTransformer.

Definition at line 57 of file point_cloud_transformers.cpp.

void rviz::IntensityPCTransformer::setAutoComputeIntensityBounds ( bool  compute  ) 

Definition at line 228 of file point_cloud_transformers.cpp.

void rviz::IntensityPCTransformer::setMaxColor ( const Color color  ) 

Definition at line 184 of file point_cloud_transformers.cpp.

void rviz::IntensityPCTransformer::setMaxIntensity ( float  val  ) 

Definition at line 215 of file point_cloud_transformers.cpp.

void rviz::IntensityPCTransformer::setMinColor ( const Color color  ) 

Definition at line 193 of file point_cloud_transformers.cpp.

void rviz::IntensityPCTransformer::setMinIntensity ( float  val  ) 

Definition at line 202 of file point_cloud_transformers.cpp.

uint8_t rviz::IntensityPCTransformer::supports ( const sensor_msgs::PointCloud2ConstPtr &  cloud  )  [virtual]

Returns a level of support for a specific cloud. This level of support is a mask using the SupportLevel enum.

Implements rviz::PointCloudTransformer.

Definition at line 41 of file point_cloud_transformers.cpp.

bool rviz::IntensityPCTransformer::transform ( const sensor_msgs::PointCloud2ConstPtr &  cloud,
uint32_t  mask,
const Ogre::Matrix4 &  transform,
PointCloud out 
) [virtual]

Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preallocated into the correct size. The mask determines which part of the cloud should be output (xyz or color). This method will only be called if supports() of the same cloud has returned a non-zero mask, and will only be called with masks compatible with the one returned from supports().

Implements rviz::PointCloudTransformer.

Definition at line 73 of file point_cloud_transformers.cpp.


Member Data Documentation

Definition at line 139 of file point_cloud_transformers.h.

Definition at line 144 of file point_cloud_transformers.h.

Definition at line 140 of file point_cloud_transformers.h.

Definition at line 136 of file point_cloud_transformers.h.

Definition at line 143 of file point_cloud_transformers.h.

Definition at line 138 of file point_cloud_transformers.h.

Definition at line 146 of file point_cloud_transformers.h.

Definition at line 135 of file point_cloud_transformers.h.

Definition at line 142 of file point_cloud_transformers.h.

Definition at line 137 of file point_cloud_transformers.h.

Definition at line 145 of file point_cloud_transformers.h.

Reimplemented from rviz::PointCloudTransformer.

Definition at line 148 of file point_cloud_transformers.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): Josh Faust
autogenerated on Fri Jan 11 09:36:32 2013