Go to the documentation of this file.
30 #ifndef RVIZ_POINT_CLOUD_COMMON_H
31 #define RVIZ_POINT_CLOUD_COMMON_H
33 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
41 #include <boost/shared_ptr.hpp>
42 #include <boost/thread/mutex.hpp>
43 #include <boost/thread/recursive_mutex.hpp>
49 #include <sensor_msgs/PointCloud.h>
50 #include <sensor_msgs/PointCloud2.h>
66 struct IndexAndMessage;
72 typedef std::vector<std::string>
V_string;
125 void update(
float wall_dt,
float ros_dt);
127 void addMessage(
const sensor_msgs::PointCloudConstPtr& cloud);
128 void addMessage(
const sensor_msgs::PointCloud2ConstPtr& cloud);
167 void processMessage(
const sensor_msgs::PointCloud2ConstPtr& cloud);
258 #endif // RVIZ_POINT_CLOUD_COMMON_H
std::map< std::string, TransformerInfo > M_TransformerInfo
void getAABBs(const Picked &obj, V_AABB &aabbs) override
void updateBillboardSize()
boost::shared_ptr< PointCloudSelectionHandler > PointCloudSelectionHandlerPtr
void setAutoSize(bool auto_size)
boost::shared_ptr< CloudInfo > CloudInfoPtr
QHash< IndexAndMessage, Property * > property_hash_
void destroyProperties(const Picked &obj, Property *parent_property) override
Destroy all properties for the given picked object(s).
EnumProperty * xyz_transformer_property_
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
void update(float wall_dt, float ros_dt)
float getSelectionBoxSize()
sensor_msgs::PointCloud2ConstPtr message_
Property specialized to provide getter for booleans.
std::list< CloudInfoPtr > L_CloudInfo
void updateTransformers(const sensor_msgs::PointCloud2ConstPtr &cloud)
void setXyzTransformerOptions(EnumProperty *prop)
void preRenderPass(uint32_t pass) override
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
Ogre::SceneManager * manager_
PointCloudSelectionHandler(float box_size, PointCloudCommon::CloudInfo *cloud_info, DisplayContext *context)
BoolProperty * selectable_property_
boost::mutex new_clouds_mutex_
void setBoxSize(float size)
FloatProperty * point_world_size_property_
EnumProperty * style_property_
PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
Property specialized to enforce floating point max/min.
bool new_color_transformer_
A single element of a property tree, with a name, value, description, and possibly children.
void updateXyzTransformer()
bool new_xyz_transformer_
std::vector< std::string > V_string
DisplayContext * context_
void createProperties(const Picked &obj, Property *parent_property) override
Override to create properties of the given picked object(s).
FloatProperty * point_pixel_size_property_
void setPropertiesHidden(const QList< Property * > &props, bool hide)
void processMessage(const sensor_msgs::PointCloud2ConstPtr &cloud)
void onDeselect(const Picked &obj) override
std::vector< CloudInfoPtr > V_CloudInfo
void postRenderPass(uint32_t pass) override
boost::recursive_mutex transformers_mutex_
void onTransformerOptions(V_string &ops, uint32_t mask)
boost::shared_ptr< PointCloudTransformer > PointCloudTransformerPtr
~PointCloudCommon() override
Displays a point cloud of type sensor_msgs::PointCloud.
Pure-virtual base class for objects which give Display subclasses context in which to work.
PointCloudCommon(Display *display)
std::vector< PointCloud::Point > transformed_points_
std::vector< Ogre::AxisAlignedBox > V_AABB
EnumProperty * color_transformer_property_
bool transformCloud(const CloudInfoPtr &cloud, bool fully_update_transformers)
Transforms the cloud into the correct frame, and sets up our renderable cloud.
bool needsAdditionalRenderPass(uint32_t pass) override
PointCloudSelectionHandlerPtr selection_handler_
void fillTransformerOptions(EnumProperty *prop, uint32_t mask)
void updateColorTransformer()
std::deque< CloudInfoPtr > D_CloudInfo
Ogre::Quaternion orientation_
void setColorTransformerOptions(EnumProperty *prop)
std::queue< CloudInfoPtr > Q_CloudInfo
M_TransformerInfo transformers_
L_CloudInfo obsolete_cloud_infos_
boost::shared_ptr< PointCloud > cloud_
FloatProperty * alpha_property_
PointCloudCommon::CloudInfo * cloud_info_
PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
pluginlib::ClassLoader< PointCloudTransformer > * transformer_class_loader_
Ogre::SceneNode * scene_node_
void onSelect(const Picked &obj) override
FloatProperty * decay_time_property_
~PointCloudSelectionHandler() override
Ogre::SceneNode * scene_node_
V_CloudInfo new_cloud_infos_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10