rviz::AxisColorPCTransformer Class Reference

#include <point_cloud_transformers.h>

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

List of all members.

Public Types

enum  Axis { AXIS_X, AXIS_Y, AXIS_Z }

Public Member Functions

 AxisColorPCTransformer ()
virtual void createProperties (PropertyManager *property_man, const Property *&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 getAutoComputeBounds ()
int getAxis ()
float getMaxValue ()
float getMinValue ()
bool getUseFixedFrame ()
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 setAutoComputeBounds (bool compute)
void setAxis (int axis)
void setMaxValue (float val)
void setMinValue (float val)
void setUseFixedFrame (bool use)
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, V_PointCloudPoint &points_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_bounds_
Propertyauto_compute_bounds_property_
int axis_
EnumPropertyaxis_property_
float max_value_
FloatPropertymax_value_property_
float min_value_
FloatPropertymin_value_property_
bool use_fixed_frame_
Propertyuse_fixed_frame_property_

Detailed Description

Definition at line 218 of file point_cloud_transformers.h.


Member Enumeration Documentation

Enumerator:
AXIS_X 
AXIS_Y 
AXIS_Z 

Definition at line 245 of file point_cloud_transformers.h.


Constructor & Destructor Documentation

rviz::AxisColorPCTransformer::AxisColorPCTransformer (  )  [inline]

Definition at line 221 of file point_cloud_transformers.h.


Member Function Documentation

void rviz::AxisColorPCTransformer::createProperties ( PropertyManager *  property_man,
const Property *&  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 600 of file point_cloud_transformers.cpp.

bool rviz::AxisColorPCTransformer::getAutoComputeBounds (  )  [inline]

Definition at line 240 of file point_cloud_transformers.h.

int rviz::AxisColorPCTransformer::getAxis (  )  [inline]

Definition at line 253 of file point_cloud_transformers.h.

float rviz::AxisColorPCTransformer::getMaxValue (  )  [inline]

Definition at line 238 of file point_cloud_transformers.h.

float rviz::AxisColorPCTransformer::getMinValue (  )  [inline]

Definition at line 237 of file point_cloud_transformers.h.

bool rviz::AxisColorPCTransformer::getUseFixedFrame (  )  [inline]

Definition at line 243 of file point_cloud_transformers.h.

uint8_t rviz::AxisColorPCTransformer::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 534 of file point_cloud_transformers.cpp.

void rviz::AxisColorPCTransformer::setAutoComputeBounds ( bool  compute  ) 

Definition at line 685 of file point_cloud_transformers.cpp.

void rviz::AxisColorPCTransformer::setAxis ( int  axis  ) 

Definition at line 652 of file point_cloud_transformers.cpp.

void rviz::AxisColorPCTransformer::setMaxValue ( float  val  ) 

Definition at line 672 of file point_cloud_transformers.cpp.

void rviz::AxisColorPCTransformer::setMinValue ( float  val  ) 

Definition at line 659 of file point_cloud_transformers.cpp.

void rviz::AxisColorPCTransformer::setUseFixedFrame ( bool  use  ) 

Definition at line 645 of file point_cloud_transformers.cpp.

uint8_t rviz::AxisColorPCTransformer::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 529 of file point_cloud_transformers.cpp.

bool rviz::AxisColorPCTransformer::transform ( const sensor_msgs::PointCloud2ConstPtr &  cloud,
uint32_t  mask,
const Ogre::Matrix4 &  transform,
V_PointCloudPoint 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 539 of file point_cloud_transformers.cpp.


Member Data Documentation

Definition at line 260 of file point_cloud_transformers.h.

Definition at line 265 of file point_cloud_transformers.h.

Definition at line 263 of file point_cloud_transformers.h.

Definition at line 268 of file point_cloud_transformers.h.

Definition at line 258 of file point_cloud_transformers.h.

Definition at line 267 of file point_cloud_transformers.h.

Definition at line 257 of file point_cloud_transformers.h.

Definition at line 266 of file point_cloud_transformers.h.

Definition at line 261 of file point_cloud_transformers.h.

Definition at line 269 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): Dave Hershberger, Josh Faust
autogenerated on Wed Jun 6 11:25:47 2012