#include <point_cloud_transformers.h>
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 std::string & | getChannelName () |
const Color & | getMaxColor () |
float | getMaxIntensity () |
const Color & | getMinColor () |
float | getMinIntensity () |
bool | getUseFullRGBColors () |
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 | setChannelName (const std::string &channel) |
void | setMaxColor (const Color &color) |
void | setMaxIntensity (float val) |
void | setMinColor (const Color &color) |
void | setMinIntensity (float val) |
void | setUseFullRGBColors (bool full_rgb) |
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() | |
void | updateChannels (const sensor_msgs::PointCloud2ConstPtr &cloud) |
Private Attributes | |
bool | auto_compute_intensity_bounds_ |
BoolPropertyWPtr | auto_compute_intensity_bounds_property_ |
V_string | available_channels_ |
EditEnumPropertyWPtr | channel_name_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_ |
std::string | selected_channel_ |
bool | use_full_rgb_colors_ |
BoolPropertyWPtr | use_full_rgb_colors_property_ |
Definition at line 107 of file point_cloud_transformers.h.
rviz::IntensityPCTransformer::IntensityPCTransformer | ( | ) | [inline] |
Definition at line 110 of file point_cloud_transformers.h.
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 154 of file point_cloud_transformers.cpp.
Definition at line 139 of file point_cloud_transformers.h.
const std::string& rviz::IntensityPCTransformer::getChannelName | ( | ) | [inline] |
Definition at line 142 of file point_cloud_transformers.h.
const Color& rviz::IntensityPCTransformer::getMaxColor | ( | ) | [inline] |
Definition at line 132 of file point_cloud_transformers.h.
float rviz::IntensityPCTransformer::getMaxIntensity | ( | ) | [inline] |
Definition at line 137 of file point_cloud_transformers.h.
const Color& rviz::IntensityPCTransformer::getMinColor | ( | ) | [inline] |
Definition at line 133 of file point_cloud_transformers.h.
float rviz::IntensityPCTransformer::getMinIntensity | ( | ) | [inline] |
Definition at line 136 of file point_cloud_transformers.h.
bool rviz::IntensityPCTransformer::getUseFullRGBColors | ( | ) | [inline] |
Definition at line 141 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 146 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 65 of file point_cloud_transformers.cpp.
void rviz::IntensityPCTransformer::setAutoComputeIntensityBounds | ( | bool | compute | ) |
Definition at line 306 of file point_cloud_transformers.cpp.
void rviz::IntensityPCTransformer::setChannelName | ( | const std::string & | channel | ) |
Definition at line 220 of file point_cloud_transformers.cpp.
void rviz::IntensityPCTransformer::setMaxColor | ( | const Color & | color | ) |
Definition at line 262 of file point_cloud_transformers.cpp.
void rviz::IntensityPCTransformer::setMaxIntensity | ( | float | val | ) |
Definition at line 293 of file point_cloud_transformers.cpp.
void rviz::IntensityPCTransformer::setMinColor | ( | const Color & | color | ) |
Definition at line 271 of file point_cloud_transformers.cpp.
void rviz::IntensityPCTransformer::setMinIntensity | ( | float | val | ) |
Definition at line 280 of file point_cloud_transformers.cpp.
void rviz::IntensityPCTransformer::setUseFullRGBColors | ( | bool | full_rgb | ) |
Definition at line 326 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 59 of file point_cloud_transformers.cpp.
bool rviz::IntensityPCTransformer::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 70 of file point_cloud_transformers.cpp.
void rviz::IntensityPCTransformer::updateChannels | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) |
Definition at line 234 of file point_cloud_transformers.cpp.
Definition at line 151 of file point_cloud_transformers.h.
BoolPropertyWPtr rviz::IntensityPCTransformer::auto_compute_intensity_bounds_property_ [private] |
Definition at line 159 of file point_cloud_transformers.h.
Definition at line 155 of file point_cloud_transformers.h.
EditEnumPropertyWPtr rviz::IntensityPCTransformer::channel_name_property_ [private] |
Definition at line 163 of file point_cloud_transformers.h.
Definition at line 153 of file point_cloud_transformers.h.
Definition at line 148 of file point_cloud_transformers.h.
ColorPropertyWPtr rviz::IntensityPCTransformer::max_color_property_ [private] |
Definition at line 158 of file point_cloud_transformers.h.
float rviz::IntensityPCTransformer::max_intensity_ [private] |
Definition at line 150 of file point_cloud_transformers.h.
FloatPropertyWPtr rviz::IntensityPCTransformer::max_intensity_property_ [private] |
Definition at line 162 of file point_cloud_transformers.h.
Definition at line 147 of file point_cloud_transformers.h.
ColorPropertyWPtr rviz::IntensityPCTransformer::min_color_property_ [private] |
Definition at line 157 of file point_cloud_transformers.h.
float rviz::IntensityPCTransformer::min_intensity_ [private] |
Definition at line 149 of file point_cloud_transformers.h.
FloatPropertyWPtr rviz::IntensityPCTransformer::min_intensity_property_ [private] |
Definition at line 161 of file point_cloud_transformers.h.
Reimplemented from rviz::PointCloudTransformer.
Definition at line 165 of file point_cloud_transformers.h.
std::string rviz::IntensityPCTransformer::selected_channel_ [private] |
Definition at line 154 of file point_cloud_transformers.h.
Definition at line 152 of file point_cloud_transformers.h.
BoolPropertyWPtr rviz::IntensityPCTransformer::use_full_rgb_colors_property_ [private] |
Definition at line 160 of file point_cloud_transformers.h.