Displays a point cloud of type sensor_msgs::PointCloud. More...
#include <point_cloud_common.h>
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.
typedef boost::shared_ptr<CloudInfo> rviz::PointCloudCommon::CloudInfoPtr |
Definition at line 113 of file point_cloud_common.h.
typedef std::deque<CloudInfoPtr> rviz::PointCloudCommon::D_CloudInfo |
Definition at line 114 of file point_cloud_common.h.
typedef std::list<CloudInfoPtr> rviz::PointCloudCommon::L_CloudInfo |
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.
typedef std::queue<CloudInfoPtr> rviz::PointCloudCommon::Q_CloudInfo |
Definition at line 116 of file point_cloud_common.h.
typedef std::vector<CloudInfoPtr> rviz::PointCloudCommon::V_CloudInfo |
Definition at line 115 of file point_cloud_common.h.
rviz::PointCloudCommon::PointCloudCommon | ( | Display * | display | ) |
Definition at line 323 of file point_cloud_common.cpp.
Definition at line 394 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::addMessage | ( | const sensor_msgs::PointCloudConstPtr & | cloud | ) |
Definition at line 920 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::addMessage | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) |
Definition at line 927 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::causeRetransform | ( | ) | [slot] |
Definition at line 521 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::fillTransformerOptions | ( | EnumProperty * | prop, |
uint32_t | mask | ||
) | [private] |
Definition at line 952 of file point_cloud_common.cpp.
Definition at line 937 of file point_cloud_common.cpp.
Definition at line 131 of file point_cloud_common.h.
PointCloudTransformerPtr rviz::PointCloudCommon::getColorTransformer | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [private] |
Definition at line 779 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 977 of file point_cloud_common.cpp.
PointCloudTransformerPtr rviz::PointCloudCommon::getXYZTransformer | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [private] |
Definition at line 763 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::initialize | ( | DisplayContext * | context, |
Ogre::SceneNode * | scene_node | ||
) |
Definition at line 381 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::loadTransformers | ( | ) | [private] |
Definition at line 401 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 727 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::reset | ( | ) |
Definition at line 514 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::retransform | ( | ) | [private] |
Definition at line 796 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::setAutoSize | ( | bool | auto_size | ) |
Definition at line 436 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::setColorTransformerOptions | ( | EnumProperty * | prop | ) | [private, slot] |
Definition at line 947 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::setPropertiesHidden | ( | const QList< Property * > & | props, |
bool | hide | ||
) | [private] |
Definition at line 643 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::setXyzTransformerOptions | ( | EnumProperty * | prop | ) | [private, slot] |
Definition at line 942 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 811 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::update | ( | float | wall_dt, |
float | ros_dt | ||
) |
Definition at line 526 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::updateAlpha | ( | ) | [private, slot] |
Definition at line 447 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::updateBillboardSize | ( | ) | [private, slot] |
Definition at line 497 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::updateColorTransformer | ( | ) | [private, slot] |
Definition at line 752 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::updateSelectable | ( | ) | [private, slot] |
Definition at line 455 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::updateStatus | ( | ) | [private] |
Definition at line 720 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::updateStyle | ( | ) | [private, slot] |
Definition at line 477 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::updateTransformers | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [private] |
Definition at line 651 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::updateXyzTransformer | ( | ) | [private, slot] |
Definition at line 741 of file point_cloud_common.cpp.
friend class PointCloudSelectionHandler [friend] |
Definition at line 217 of file point_cloud_common.h.
Definition at line 140 of file point_cloud_common.h.
Definition at line 135 of file point_cloud_common.h.
Definition at line 184 of file point_cloud_common.h.
Definition at line 186 of file point_cloud_common.h.
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.
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.
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.
Definition at line 193 of file point_cloud_common.h.
Definition at line 139 of file point_cloud_common.h.
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.
Definition at line 137 of file point_cloud_common.h.
Definition at line 183 of file point_cloud_common.h.
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.
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.
Definition at line 141 of file point_cloud_common.h.