Class PointCloudCommon
Defined in File point_cloud_common.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public QObject
Class Documentation
-
class PointCloudCommon : public QObject
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.
Public Types
-
typedef std::deque<CloudInfoPtr> D_CloudInfo
-
typedef std::vector<CloudInfoPtr> V_CloudInfo
-
typedef std::list<CloudInfoPtr> L_CloudInfo
Public Functions
-
explicit PointCloudCommon(rviz_common::Display *display)
-
void initialize(rviz_common::DisplayContext *context, Ogre::SceneNode *scene_node)
-
void reset()
-
void update(float wall_dt, float ros_dt)
-
inline rviz_common::Display *getDisplay()
-
void onDisable()
-
void setAutoSize(bool auto_size)
Public Members
-
bool auto_size_
-
rviz_common::properties::BoolProperty *selectable_property_
-
rviz_common::properties::FloatProperty *point_world_size_property_
-
rviz_common::properties::FloatProperty *point_pixel_size_property_
-
rviz_common::properties::FloatProperty *alpha_property_
-
rviz_common::properties::EnumProperty *xyz_transformer_property_
-
rviz_common::properties::EnumProperty *color_transformer_property_
-
rviz_common::properties::EnumProperty *style_property_
-
rviz_common::properties::FloatProperty *decay_time_property_
Public Slots
-
void causeRetransform()
Protected Functions
-
typedef std::deque<CloudInfoPtr> D_CloudInfo