Displays a point cloud of type sensor_msgs::PointCloud. More...
#include <point_cloud_common.h>
Classes | |
struct | CloudInfo |
struct | TransformerInfo |
Public Types | |
typedef boost::shared_ptr< CloudInfo > | CloudInfoPtr |
typedef std::deque< CloudInfoPtr > | D_CloudInfo |
typedef std::list< CloudInfoPtr > | L_CloudInfo |
typedef std::queue< CloudInfoPtr > | Q_CloudInfo |
typedef std::vector< CloudInfoPtr > | V_CloudInfo |
Public Slots | |
void | causeRetransform () |
Public Member Functions | |
void | addMessage (const sensor_msgs::PointCloudConstPtr &cloud) |
void | addMessage (const sensor_msgs::PointCloud2ConstPtr &cloud) |
void | fixedFrameChanged () |
Display * | getDisplay () |
void | initialize (DisplayContext *context, Ogre::SceneNode *scene_node) |
PointCloudCommon (Display *display) | |
void | reset () |
void | setAutoSize (bool auto_size) |
void | update (float wall_dt, float ros_dt) |
~PointCloudCommon () override | |
Private Types | |
typedef std::map< std::string, TransformerInfo > | M_TransformerInfo |
Private Slots | |
void | setColorTransformerOptions (EnumProperty *prop) |
void | setXyzTransformerOptions (EnumProperty *prop) |
void | updateAlpha () |
void | updateBillboardSize () |
void | updateColorTransformer () |
void | updateSelectable () |
void | updateStyle () |
void | updateXyzTransformer () |
Private Member Functions | |
void | fillTransformerOptions (EnumProperty *prop, uint32_t mask) |
PointCloudTransformerPtr | getColorTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud) |
float | getSelectionBoxSize () |
PointCloudTransformerPtr | getXYZTransformer (const sensor_msgs::PointCloud2ConstPtr &cloud) |
void | loadTransformers () |
void | onTransformerOptions (V_string &ops, uint32_t mask) |
void | processMessage (const sensor_msgs::PointCloud2ConstPtr &cloud) |
void | retransform () |
void | setPropertiesHidden (const QList< Property *> &props, bool hide) |
bool | transformCloud (const CloudInfoPtr &cloud, bool fully_update_transformers) |
Transforms the cloud into the correct frame, and sets up our renderable cloud. More... | |
void | updateStatus () |
void | updateTransformers (const sensor_msgs::PointCloud2ConstPtr &cloud) |
Private Attributes | |
D_CloudInfo | cloud_infos_ |
DisplayContext * | context_ |
Display * | display_ |
bool | needs_retransform_ |
V_CloudInfo | new_cloud_infos_ |
boost::mutex | new_clouds_mutex_ |
bool | new_color_transformer_ |
bool | new_xyz_transformer_ |
L_CloudInfo | obsolete_cloud_infos_ |
Ogre::SceneNode * | scene_node_ |
pluginlib::ClassLoader< PointCloudTransformer > * | transformer_class_loader_ |
M_TransformerInfo | transformers_ |
boost::recursive_mutex | transformers_mutex_ |
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 84 of file point_cloud_common.h.
Definition at line 112 of file point_cloud_common.h.
typedef std::deque<CloudInfoPtr> rviz::PointCloudCommon::D_CloudInfo |
Definition at line 113 of file point_cloud_common.h.
typedef std::list<CloudInfoPtr> rviz::PointCloudCommon::L_CloudInfo |
Definition at line 116 of file point_cloud_common.h.
|
private |
Definition at line 200 of file point_cloud_common.h.
typedef std::queue<CloudInfoPtr> rviz::PointCloudCommon::Q_CloudInfo |
Definition at line 115 of file point_cloud_common.h.
typedef std::vector<CloudInfoPtr> rviz::PointCloudCommon::V_CloudInfo |
Definition at line 114 of file point_cloud_common.h.
rviz::PointCloudCommon::PointCloudCommon | ( | Display * | display | ) |
Definition at line 308 of file point_cloud_common.cpp.
|
override |
Definition at line 381 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::addMessage | ( | const sensor_msgs::PointCloudConstPtr & | cloud | ) |
Definition at line 938 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::addMessage | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) |
Definition at line 945 of file point_cloud_common.cpp.
|
slot |
Definition at line 514 of file point_cloud_common.cpp.
|
private |
Definition at line 965 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::fixedFrameChanged | ( | ) |
Definition at line 950 of file point_cloud_common.cpp.
|
private |
Definition at line 785 of file point_cloud_common.cpp.
|
inline |
Definition at line 130 of file point_cloud_common.h.
|
private |
Definition at line 990 of file point_cloud_common.cpp.
|
private |
Definition at line 768 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::initialize | ( | DisplayContext * | context, |
Ogre::SceneNode * | scene_node | ||
) |
Definition at line 366 of file point_cloud_common.cpp.
|
private |
Definition at line 389 of file point_cloud_common.cpp.
|
private |
|
private |
Definition at line 731 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::reset | ( | ) |
Definition at line 507 of file point_cloud_common.cpp.
|
private |
Definition at line 802 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::setAutoSize | ( | bool | auto_size | ) |
Definition at line 424 of file point_cloud_common.cpp.
|
privateslot |
Definition at line 960 of file point_cloud_common.cpp.
|
private |
Definition at line 646 of file point_cloud_common.cpp.
|
privateslot |
Definition at line 955 of file point_cloud_common.cpp.
|
private |
Transforms the cloud into the correct frame, and sets up our renderable cloud.
Definition at line 818 of file point_cloud_common.cpp.
void rviz::PointCloudCommon::update | ( | float | wall_dt, |
float | ros_dt | ||
) |
Definition at line 519 of file point_cloud_common.cpp.
|
privateslot |
Definition at line 434 of file point_cloud_common.cpp.
|
privateslot |
Definition at line 487 of file point_cloud_common.cpp.
|
privateslot |
Definition at line 756 of file point_cloud_common.cpp.
|
privateslot |
Definition at line 443 of file point_cloud_common.cpp.
|
private |
Definition at line 724 of file point_cloud_common.cpp.
|
privateslot |
Definition at line 467 of file point_cloud_common.cpp.
|
private |
Definition at line 654 of file point_cloud_common.cpp.
|
privateslot |
Definition at line 745 of file point_cloud_common.cpp.
|
friend |
Definition at line 213 of file point_cloud_common.h.
FloatProperty* rviz::PointCloudCommon::alpha_property_ |
Definition at line 140 of file point_cloud_common.h.
bool rviz::PointCloudCommon::auto_size_ |
Definition at line 135 of file point_cloud_common.h.
|
private |
Definition at line 182 of file point_cloud_common.h.
EnumProperty* rviz::PointCloudCommon::color_transformer_property_ |
Definition at line 142 of file point_cloud_common.h.
|
private |
Definition at line 211 of file point_cloud_common.h.
FloatProperty* rviz::PointCloudCommon::decay_time_property_ |
Definition at line 144 of file point_cloud_common.h.
|
private |
Definition at line 210 of file point_cloud_common.h.
|
private |
Definition at line 206 of file point_cloud_common.h.
|
private |
Definition at line 186 of file point_cloud_common.h.
|
private |
Definition at line 187 of file point_cloud_common.h.
|
private |
Definition at line 205 of file point_cloud_common.h.
|
private |
Definition at line 204 of file point_cloud_common.h.
|
private |
Definition at line 189 of file point_cloud_common.h.
FloatProperty* rviz::PointCloudCommon::point_pixel_size_property_ |
Definition at line 139 of file point_cloud_common.h.
FloatProperty* rviz::PointCloudCommon::point_world_size_property_ |
Definition at line 138 of file point_cloud_common.h.
|
private |
Definition at line 184 of file point_cloud_common.h.
BoolProperty* rviz::PointCloudCommon::selectable_property_ |
Definition at line 137 of file point_cloud_common.h.
EnumProperty* rviz::PointCloudCommon::style_property_ |
Definition at line 143 of file point_cloud_common.h.
|
private |
Definition at line 208 of file point_cloud_common.h.
|
private |
Definition at line 203 of file point_cloud_common.h.
|
private |
Definition at line 202 of file point_cloud_common.h.
EnumProperty* rviz::PointCloudCommon::xyz_transformer_property_ |
Definition at line 141 of file point_cloud_common.h.