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);
165 bool transformCloud(
const CloudInfoPtr& cloud,
bool fully_update_transformers);
167 void processMessage(
const sensor_msgs::PointCloud2ConstPtr& cloud);
170 PointCloudTransformerPtr
getXYZTransformer(
const sensor_msgs::PointCloud2ConstPtr& cloud);
171 PointCloudTransformerPtr
getColorTransformer(
const sensor_msgs::PointCloud2ConstPtr& cloud);
224 void createProperties(
const Picked& obj,
Property* parent_property)
override;
225 void destroyProperties(
const Picked& obj,
Property* parent_property)
override;
232 void preRenderPass(uint32_t pass)
override;
233 void postRenderPass(uint32_t pass)
override;
235 void onSelect(
const Picked& obj)
override;
236 void onDeselect(
const Picked& obj)
override;
238 void getAABBs(
const Picked& obj,
V_AABB& aabbs)
override;
247 return !boxes_.empty();
258 #endif // RVIZ_POINT_CLOUD_COMMON_H float getSelectionBoxSize()
void setXyzTransformerOptions(EnumProperty *prop)
FloatProperty * alpha_property_
pluginlib::ClassLoader< PointCloudTransformer > * transformer_class_loader_
void setPropertiesHidden(const QList< Property *> &props, bool hide)
void updateTransformers(const sensor_msgs::PointCloud2ConstPtr &cloud)
PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
std::vector< PointCloud::Point > transformed_points_
boost::mutex new_clouds_mutex_
bool needsAdditionalRenderPass(uint32_t pass) override
std::map< std::string, TransformerInfo > M_TransformerInfo
void updateXyzTransformer()
FloatProperty * point_world_size_property_
boost::shared_ptr< CloudInfo > CloudInfoPtr
FloatProperty * decay_time_property_
A single element of a property tree, with a name, value, description, and possibly children...
Ogre::SceneNode * scene_node_
bool new_xyz_transformer_
EnumProperty * xyz_transformer_property_
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
Ogre::Quaternion orientation_
friend class PointCloudSelectionHandler
Property specialized to enforce floating point max/min.
QHash< IndexAndMessage, Property * > property_hash_
boost::shared_ptr< PointCloudTransformer > PointCloudTransformerPtr
boost::recursive_mutex transformers_mutex_
std::list< CloudInfoPtr > L_CloudInfo
Ogre::SceneManager * manager_
Displays a point cloud of type sensor_msgs::PointCloud.
PointCloudCommon(Display *display)
Pure-virtual base class for objects which give Display subclasses context in which to work...
std::vector< Ogre::AxisAlignedBox > V_AABB
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
~PointCloudCommon() override
EnumProperty * style_property_
void fillTransformerOptions(EnumProperty *prop, uint32_t mask)
EnumProperty * color_transformer_property_
bool new_color_transformer_
BoolProperty * selectable_property_
PointCloudCommon::CloudInfo * cloud_info_
M_TransformerInfo transformers_
std::vector< CloudInfoPtr > V_CloudInfo
void setColorTransformerOptions(EnumProperty *prop)
FloatProperty * point_pixel_size_property_
DisplayContext * context_
L_CloudInfo obsolete_cloud_infos_
std::vector< std::string > V_string
boost::shared_ptr< PointCloudSelectionHandler > PointCloudSelectionHandlerPtr
boost::shared_ptr< PointCloud > cloud_
Property specialized to provide getter for booleans.
void processMessage(const sensor_msgs::PointCloud2ConstPtr &cloud)
void setAutoSize(bool auto_size)
Ogre::SceneNode * scene_node_
V_CloudInfo new_cloud_infos_
void onTransformerOptions(V_string &ops, uint32_t mask)
bool transformCloud(const CloudInfoPtr &cloud, bool fully_update_transformers)
Transforms the cloud into the correct frame, and sets up our renderable cloud.
sensor_msgs::PointCloud2ConstPtr message_
void updateColorTransformer()
std::queue< CloudInfoPtr > Q_CloudInfo
void updateBillboardSize()
void setBoxSize(float size)
void update(float wall_dt, float ros_dt)
std::deque< CloudInfoPtr > D_CloudInfo
PointCloudSelectionHandlerPtr selection_handler_