Displays a point cloud of type sensor_msgs::PointCloud. More...
#include <point_cloud_base.h>
Classes | |
struct | CloudInfo |
struct | TransformerInfo |
Public Types | |
enum | ChannelRender { Intensity, Curvature, ColorRGBSpace, NormalSphere, ChannelRenderCount } |
The different channels that we support rendering. More... | |
enum | Style { Points, Billboards, BillboardSpheres, Boxes, StyleCount } |
The different styles of pointcloud drawing. More... | |
Public Member Functions | |
void | causeRetransform () |
virtual void | createProperties () |
Called from setPropertyManager, gives the display a chance to create some properties immediately. | |
virtual void | fixedFrameChanged () |
Override to handle changes to fixed_frame_. This base class implementation does nothing. | |
float | getAlpha () |
float | getBillboardSize () |
float | getDecayTime () |
bool | getSelectable () |
int | getStyle () |
virtual void | hideVisible () |
Hides all visible parts of this display, so they do not show up when the scene is rendered. | |
void | onInitialize () |
Override this function to do subclass-specific initialization. | |
PointCloudBase () | |
virtual void | reset () |
Called to tell the display to clear its state. | |
virtual void | restoreVisible () |
Restores the display to the state it was in before hideVisible() was called. | |
void | setAlpha (float alpha) |
void | setBillboardSize (float size) |
Sets the size each point will be when drawn in 3D as a billboard. | |
void | setDecayTime (float time) |
Set the amount of time each cloud should stick around for. | |
void | setSelectable (bool selectable) |
void | setStyle (int style) |
Set the rendering style. | |
virtual void | update (float wall_dt, float ros_dt) |
Called periodically by the visualization panel. | |
~PointCloudBase () | |
Protected Types | |
typedef std::map< std::string, TransformerInfo > | M_TransformerInfo |
typedef std::vector < PointCloud::Point > | V_Point |
typedef std::vector< V_Point > | VV_Point |
Protected Member Functions | |
void | addMessage (const sensor_msgs::PointCloudConstPtr &cloud) |
void | addMessage (const sensor_msgs::PointCloud2ConstPtr &cloud) |
const std::string & | getColorTransformer () |
PointCloudTransformerPtr | getColorTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud) |
const std::string & | getXYZTransformer () |
PointCloudTransformerPtr | getXYZTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud) |
void | loadTransformers () |
virtual void | onDisable () |
Derived classes override this to do the actual work of disabling themselves. | |
virtual void | onEnable () |
Derived classes override this to do the actual work of enabling themselves. | |
void | onTransformerOptions (V_string &ops, uint32_t mask) |
void | processMessage (const sensor_msgs::PointCloud2ConstPtr &cloud) |
void | retransform () |
void | setColorTransformer (const std::string &name) |
void | setXYZTransformer (const std::string &name) |
bool | transformCloud (const CloudInfoPtr &cloud, V_Point &points, bool fully_update_transformers) |
Transforms the cloud into the correct frame, and sets up our renderable cloud. | |
void | updateStatus () |
void | updateTransformers (const sensor_msgs::PointCloud2ConstPtr &cloud, bool fully_update) |
Protected Attributes | |
float | alpha_ |
FloatPropertyWPtr | alpha_property_ |
float | billboard_size_ |
Size to draw our billboards. | |
FloatPropertyWPtr | billboard_size_property_ |
ros::CallbackQueue | cbqueue_ |
PointCloud * | cloud_ |
D_CloudInfo | clouds_ |
boost::mutex | clouds_mutex_ |
CollObjectHandle | coll_handle_ |
PointCloudSelectionHandlerPtr | coll_handler_ |
std::string | color_transformer_ |
EditEnumPropertyWPtr | color_transformer_property_ |
FloatPropertyWPtr | decay_time_property_ |
bool | hidden_ |
uint32_t | messages_received_ |
bool | needs_retransform_ |
bool | new_cloud_ |
V_CloudInfo | new_clouds_ |
boost::mutex | new_clouds_mutex_ |
bool | new_color_transformer_ |
VV_Point | new_points_ |
bool | new_xyz_transformer_ |
float | point_decay_time_ |
How long clouds should stick around for before they are culled. | |
Ogre::SceneNode * | scene_node_ |
bool | selectable_ |
BoolPropertyWPtr | selectable_property_ |
ros::AsyncSpinner | spinner_ |
int | style_ |
Our rendering style. | |
EnumPropertyWPtr | style_property_ |
uint32_t | total_point_count_ |
pluginlib::ClassLoader < PointCloudTransformer > * | transformer_class_loader_ |
M_TransformerInfo | transformers_ |
boost::recursive_mutex | transformers_mutex_ |
std::string | xyz_transformer_ |
EditEnumPropertyWPtr | xyz_transformer_property_ |
Private Types | |
typedef boost::shared_ptr < CloudInfo > | CloudInfoPtr |
typedef std::deque< CloudInfoPtr > | D_CloudInfo |
typedef std::queue< CloudInfoPtr > | Q_CloudInfo |
typedef std::vector< CloudInfoPtr > | V_CloudInfo |
Friends | |
class | PointCloudSelectionHandler |
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 76 of file point_cloud_base.h.
typedef boost::shared_ptr<CloudInfo> rviz::PointCloudBase::CloudInfoPtr [private] |
Definition at line 92 of file point_cloud_base.h.
typedef std::deque<CloudInfoPtr> rviz::PointCloudBase::D_CloudInfo [private] |
Definition at line 93 of file point_cloud_base.h.
typedef std::map<std::string, TransformerInfo> rviz::PointCloudBase::M_TransformerInfo [protected] |
Definition at line 226 of file point_cloud_base.h.
typedef std::queue<CloudInfoPtr> rviz::PointCloudBase::Q_CloudInfo [private] |
Definition at line 95 of file point_cloud_base.h.
typedef std::vector<CloudInfoPtr> rviz::PointCloudBase::V_CloudInfo [private] |
Definition at line 94 of file point_cloud_base.h.
typedef std::vector<PointCloud::Point> rviz::PointCloudBase::V_Point [protected] |
Definition at line 176 of file point_cloud_base.h.
typedef std::vector<V_Point> rviz::PointCloudBase::VV_Point [protected] |
Definition at line 177 of file point_cloud_base.h.
The different channels that we support rendering.
Intensity |
Intensity data. |
Curvature |
Surface curvature estimates. |
ColorRGBSpace |
RGB Color. |
NormalSphere |
Use the nx-ny-nz (normal coordinates) instead of x-y-z. |
ChannelRenderCount |
Definition at line 116 of file point_cloud_base.h.
The different styles of pointcloud drawing.
Definition at line 102 of file point_cloud_base.h.
Definition at line 349 of file point_cloud_base.cpp.
Definition at line 419 of file point_cloud_base.cpp.
void rviz::PointCloudBase::addMessage | ( | const sensor_msgs::PointCloudConstPtr & | cloud | ) | [protected] |
Definition at line 1082 of file point_cloud_base.cpp.
void rviz::PointCloudBase::addMessage | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [protected] |
Definition at line 1089 of file point_cloud_base.cpp.
Definition at line 591 of file point_cloud_base.cpp.
void rviz::PointCloudBase::createProperties | ( | ) | [virtual] |
Called from setPropertyManager, gives the display a chance to create some properties immediately.
When this function is called, the property_manager_ member is valid and will stay valid
Reimplemented from rviz::Display.
Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.
Definition at line 1131 of file point_cloud_base.cpp.
void rviz::PointCloudBase::fixedFrameChanged | ( | ) | [virtual] |
Override to handle changes to fixed_frame_. This base class implementation does nothing.
Reimplemented from rviz::Display.
Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.
Definition at line 1101 of file point_cloud_base.cpp.
float rviz::PointCloudBase::getAlpha | ( | ) | [inline] |
Definition at line 152 of file point_cloud_base.h.
float rviz::PointCloudBase::getBillboardSize | ( | ) | [inline] |
Definition at line 148 of file point_cloud_base.h.
const std::string& rviz::PointCloudBase::getColorTransformer | ( | ) | [inline, protected] |
Definition at line 192 of file point_cloud_base.h.
PointCloudTransformerPtr rviz::PointCloudBase::getColorTransformer | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [protected] |
Definition at line 918 of file point_cloud_base.cpp.
float rviz::PointCloudBase::getDecayTime | ( | ) | [inline] |
Definition at line 150 of file point_cloud_base.h.
bool rviz::PointCloudBase::getSelectable | ( | ) | [inline] |
Definition at line 155 of file point_cloud_base.h.
int rviz::PointCloudBase::getStyle | ( | ) | [inline] |
Definition at line 149 of file point_cloud_base.h.
const std::string& rviz::PointCloudBase::getXYZTransformer | ( | ) | [inline, protected] |
Definition at line 191 of file point_cloud_base.h.
PointCloudTransformerPtr rviz::PointCloudBase::getXYZTransformer | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [protected] |
Definition at line 902 of file point_cloud_base.cpp.
void rviz::PointCloudBase::hideVisible | ( | ) | [virtual] |
Hides all visible parts of this display, so they do not show up when the scene is rendered.
Reimplemented from rviz::Display.
Definition at line 387 of file point_cloud_base.cpp.
void rviz::PointCloudBase::loadTransformers | ( | ) | [protected] |
Definition at line 446 of file point_cloud_base.cpp.
void rviz::PointCloudBase::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Implements rviz::Display.
Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.
Definition at line 583 of file point_cloud_base.cpp.
void rviz::PointCloudBase::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Implements rviz::Display.
Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.
Definition at line 579 of file point_cloud_base.cpp.
void rviz::PointCloudBase::onInitialize | ( | ) | [virtual] |
Override this function to do subclass-specific initialization.
This is called after vis_manager_ and scene_manager_ are set.
Reimplemented from rviz::Display.
Reimplemented in rviz::LaserScanDisplay, rviz::PointCloud2Display, and rviz::PointCloudDisplay.
Definition at line 369 of file point_cloud_base.cpp.
void rviz::PointCloudBase::onTransformerOptions | ( | V_string & | ops, |
uint32_t | mask | ||
) | [protected] |
Definition at line 1106 of file point_cloud_base.cpp.
void rviz::PointCloudBase::processMessage | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [protected] |
Definition at line 843 of file point_cloud_base.cpp.
void rviz::PointCloudBase::reset | ( | ) | [virtual] |
Called to tell the display to clear its state.
Reimplemented from rviz::Display.
Definition at line 1217 of file point_cloud_base.cpp.
void rviz::PointCloudBase::restoreVisible | ( | ) | [virtual] |
Restores the display to the state it was in before hideVisible() was called.
Reimplemented from rviz::Display.
Definition at line 397 of file point_cloud_base.cpp.
void rviz::PointCloudBase::retransform | ( | ) | [protected] |
Definition at line 934 of file point_cloud_base.cpp.
void rviz::PointCloudBase::setAlpha | ( | float | alpha | ) |
Definition at line 482 of file point_cloud_base.cpp.
void rviz::PointCloudBase::setBillboardSize | ( | float | size | ) |
Sets the size each point will be when drawn in 3D as a billboard.
size | The size |
Definition at line 568 of file point_cloud_base.cpp.
void rviz::PointCloudBase::setColorTransformer | ( | const std::string & | name | ) | [protected] |
Definition at line 882 of file point_cloud_base.cpp.
void rviz::PointCloudBase::setDecayTime | ( | float | time | ) |
Set the amount of time each cloud should stick around for.
time | Decay time, in seconds |
Definition at line 523 of file point_cloud_base.cpp.
void rviz::PointCloudBase::setSelectable | ( | bool | selectable | ) |
Definition at line 491 of file point_cloud_base.cpp.
void rviz::PointCloudBase::setStyle | ( | int | style | ) |
Set the rendering style.
style | The rendering style |
Definition at line 532 of file point_cloud_base.cpp.
void rviz::PointCloudBase::setXYZTransformer | ( | const std::string & | name | ) | [protected] |
Definition at line 862 of file point_cloud_base.cpp.
bool rviz::PointCloudBase::transformCloud | ( | const CloudInfoPtr & | cloud, |
V_Point & | points, | ||
bool | fully_update_transformers | ||
) | [protected] |
Transforms the cloud into the correct frame, and sets up our renderable cloud.
Definition at line 961 of file point_cloud_base.cpp.
void rviz::PointCloudBase::update | ( | float | wall_dt, |
float | ros_dt | ||
) | [virtual] |
Called periodically by the visualization panel.
dt | Wall-clock time, in seconds, since the last time the update list was run through. |
Reimplemented from rviz::Display.
Definition at line 597 of file point_cloud_base.cpp.
void rviz::PointCloudBase::updateStatus | ( | ) | [protected] |
Definition at line 823 of file point_cloud_base.cpp.
void rviz::PointCloudBase::updateTransformers | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud, |
bool | fully_update | ||
) | [protected] |
Definition at line 723 of file point_cloud_base.cpp.
friend class PointCloudSelectionHandler [friend] |
Definition at line 259 of file point_cloud_base.h.
float rviz::PointCloudBase::alpha_ [protected] |
Definition at line 215 of file point_cloud_base.h.
FloatPropertyWPtr rviz::PointCloudBase::alpha_property_ [protected] |
Definition at line 251 of file point_cloud_base.h.
float rviz::PointCloudBase::billboard_size_ [protected] |
Size to draw our billboards.
Definition at line 237 of file point_cloud_base.h.
FloatPropertyWPtr rviz::PointCloudBase::billboard_size_property_ [protected] |
Definition at line 250 of file point_cloud_base.h.
ros::CallbackQueue rviz::PointCloudBase::cbqueue_ [protected] |
Definition at line 202 of file point_cloud_base.h.
PointCloud* rviz::PointCloudBase::cloud_ [protected] |
Definition at line 208 of file point_cloud_base.h.
D_CloudInfo rviz::PointCloudBase::clouds_ [protected] |
Definition at line 204 of file point_cloud_base.h.
boost::mutex rviz::PointCloudBase::clouds_mutex_ [protected] |
Definition at line 205 of file point_cloud_base.h.
CollObjectHandle rviz::PointCloudBase::coll_handle_ [protected] |
Definition at line 241 of file point_cloud_base.h.
Definition at line 242 of file point_cloud_base.h.
std::string rviz::PointCloudBase::color_transformer_ [protected] |
Definition at line 231 of file point_cloud_base.h.
EditEnumPropertyWPtr rviz::PointCloudBase::color_transformer_property_ [protected] |
Definition at line 253 of file point_cloud_base.h.
FloatPropertyWPtr rviz::PointCloudBase::decay_time_property_ [protected] |
Definition at line 255 of file point_cloud_base.h.
bool rviz::PointCloudBase::hidden_ [protected] |
Definition at line 257 of file point_cloud_base.h.
uint32_t rviz::PointCloudBase::messages_received_ [protected] |
Definition at line 244 of file point_cloud_base.h.
bool rviz::PointCloudBase::needs_retransform_ [protected] |
Definition at line 234 of file point_cloud_base.h.
bool rviz::PointCloudBase::new_cloud_ [protected] |
Definition at line 206 of file point_cloud_base.h.
V_CloudInfo rviz::PointCloudBase::new_clouds_ [protected] |
Definition at line 212 of file point_cloud_base.h.
boost::mutex rviz::PointCloudBase::new_clouds_mutex_ [protected] |
Definition at line 213 of file point_cloud_base.h.
bool rviz::PointCloudBase::new_color_transformer_ [protected] |
Definition at line 233 of file point_cloud_base.h.
VV_Point rviz::PointCloudBase::new_points_ [protected] |
Definition at line 211 of file point_cloud_base.h.
bool rviz::PointCloudBase::new_xyz_transformer_ [protected] |
Definition at line 232 of file point_cloud_base.h.
float rviz::PointCloudBase::point_decay_time_ [protected] |
How long clouds should stick around for before they are culled.
Definition at line 238 of file point_cloud_base.h.
Ogre::SceneNode* rviz::PointCloudBase::scene_node_ [protected] |
Definition at line 209 of file point_cloud_base.h.
bool rviz::PointCloudBase::selectable_ [protected] |
Definition at line 240 of file point_cloud_base.h.
BoolPropertyWPtr rviz::PointCloudBase::selectable_property_ [protected] |
Definition at line 249 of file point_cloud_base.h.
ros::AsyncSpinner rviz::PointCloudBase::spinner_ [protected] |
Definition at line 201 of file point_cloud_base.h.
int rviz::PointCloudBase::style_ [protected] |
Our rendering style.
Definition at line 236 of file point_cloud_base.h.
EnumPropertyWPtr rviz::PointCloudBase::style_property_ [protected] |
Definition at line 254 of file point_cloud_base.h.
uint32_t rviz::PointCloudBase::total_point_count_ [protected] |
Definition at line 245 of file point_cloud_base.h.
pluginlib::ClassLoader<PointCloudTransformer>* rviz::PointCloudBase::transformer_class_loader_ [protected] |
Definition at line 247 of file point_cloud_base.h.
M_TransformerInfo rviz::PointCloudBase::transformers_ [protected] |
Definition at line 229 of file point_cloud_base.h.
boost::recursive_mutex rviz::PointCloudBase::transformers_mutex_ [protected] |
Definition at line 228 of file point_cloud_base.h.
std::string rviz::PointCloudBase::xyz_transformer_ [protected] |
Definition at line 230 of file point_cloud_base.h.
EditEnumPropertyWPtr rviz::PointCloudBase::xyz_transformer_property_ [protected] |
Definition at line 252 of file point_cloud_base.h.