point_cloud.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef OGRE_TOOLS_OGRE_POINT_CLOUD_H
31 #define OGRE_TOOLS_OGRE_POINT_CLOUD_H
32 
33 #include <OgreSimpleRenderable.h>
34 #include <OgreMovableObject.h>
35 #include <OgreString.h>
36 #include <OgreAxisAlignedBox.h>
38 #include <OgreMaterial.h>
39 #include <OgreColourValue.h>
40 #include <OgreRoot.h>
41 #include <OgreHardwareBufferManager.h>
42 #include <OgreSharedPtr.h>
43 
44 #include <stdint.h>
45 
46 #include <vector>
47 
48 #include <boost/shared_ptr.hpp>
49 
50 namespace Ogre
51 {
52 class SceneManager;
53 class ManualObject;
54 class SceneNode;
55 class RenderQueue;
56 class Camera;
57 class RenderSystem;
58 class Matrix4;
59 } // namespace Ogre
60 
61 namespace rviz
62 {
63 class PointCloud;
64 class PointCloudRenderable : public Ogre::SimpleRenderable
65 {
66 public:
67  PointCloudRenderable(PointCloud* parent, int num_points, bool use_tex_coords);
68  ~PointCloudRenderable() override;
69 
70  using Ogre::SimpleRenderable::getRenderOperation;
71 
72  Ogre::RenderOperation* getRenderOperation()
73  {
74  return &mRenderOp;
75  }
76 
77  Ogre::HardwareVertexBufferSharedPtr getBuffer();
78 
79  Ogre::Real getBoundingRadius() const override;
80  Ogre::Real getSquaredViewDepth(const Ogre::Camera* cam) const override;
81  unsigned short getNumWorldTransforms() const override
82  {
83  return 1;
84  }
85  void getWorldTransforms(Ogre::Matrix4* xform) const override;
86  const Ogre::LightList& getLights() const override;
87 
88 private:
89  Ogre::MaterialPtr material_;
91 };
93 typedef std::vector<PointCloudRenderablePtr> V_PointCloudRenderable;
94 
108 class PointCloud : public Ogre::MovableObject
109 {
110 public:
112  {
119  };
120 
121  PointCloud();
122  ~PointCloud() override;
123 
127  void clear();
128 
133  struct Point
134  {
135  inline void setColor(float r, float g, float b, float a = 1.0)
136  {
137  color = Ogre::ColourValue(r, g, b, a);
138  }
139 
140  Ogre::Vector3 position;
141  Ogre::ColourValue color;
142  };
143 
150  void addPoints(Point* points, uint32_t num_points);
151 
156  void popPoints(uint32_t num_points);
157 
162  void setRenderMode(RenderMode mode);
169  void setDimensions(float width, float height, float depth);
170 
171  /*
172  * If set to true, the size of each point will be multiplied by it z component.
173  * (Used for depth image based point clouds)
174  */
175  void setAutoSize(bool auto_size);
176 
178  void setCommonDirection(const Ogre::Vector3& vec);
180  void setCommonUpVector(const Ogre::Vector3& vec);
181 
186  void setAlpha(float alpha, bool per_point_alpha = false);
187 
188  void setPickColor(const Ogre::ColourValue& color);
189  void setColorByIndex(bool set);
190 
191  void setHighlightColor(float r, float g, float b);
192 
193  const Ogre::String& getMovableType() const override
194  {
195  return sm_Type;
196  }
197  const Ogre::AxisAlignedBox& getBoundingBox() const override;
198  float getBoundingRadius() const override;
199  virtual void getWorldTransforms(Ogre::Matrix4* xform) const;
200  virtual unsigned short getNumWorldTransforms() const
201  {
202  return 1;
203  }
204  void _updateRenderQueue(Ogre::RenderQueue* queue) override;
205  void _notifyAttached(Ogre::Node* parent, bool isTagPoint = false) override;
206  void visitRenderables(Ogre::Renderable::Visitor* visitor, bool debugRenderables) override;
207 
208  virtual void setName(const std::string& name)
209  {
210  mName = name;
211  }
212 
213 private:
214  uint32_t getVerticesPerPoint();
216  void regenerateAll();
217  void shrinkRenderables();
218 
219  Ogre::AxisAlignedBox bounding_box_;
221 
222  typedef std::vector<Point> V_Point;
224  uint32_t point_count_;
225 
227  float width_;
228  float height_;
229  float depth_;
230  Ogre::Vector3 common_direction_;
231  Ogre::Vector3 common_up_vector_;
232 
233  Ogre::MaterialPtr point_material_;
234  Ogre::MaterialPtr square_material_;
235  Ogre::MaterialPtr flat_square_material_;
236  Ogre::MaterialPtr sphere_material_;
237  Ogre::MaterialPtr tile_material_;
238  Ogre::MaterialPtr box_material_;
239  Ogre::MaterialPtr current_material_;
240  float alpha_;
241 
243 
245 
247  Ogre::ColourValue pick_color_;
248 
249  static Ogre::String sm_Type;
250 };
251 
252 } // namespace rviz
253 
254 #endif
rviz::PointCloud
A visual representation of a set of points.
Definition: point_cloud.h:108
rviz::PointCloud::regenerateAll
void regenerateAll()
Definition: point_cloud.cpp:184
Ogre
Definition: axes_display.h:35
rviz::PointCloud::setAlpha
void setAlpha(float alpha, bool per_point_alpha=false)
Definition: point_cloud.cpp:368
rviz::PointCloud::point_count_
uint32_t point_count_
The number of points currently in points_.
Definition: point_cloud.h:224
rviz::PointCloud::width_
float width_
width
Definition: point_cloud.h:227
boost::shared_ptr
rviz::PointCloudRenderable::getRenderOperation
Ogre::RenderOperation * getRenderOperation()
Definition: point_cloud.h:72
rviz::PointCloud::addPoints
void addPoints(Point *points, uint32_t num_points)
Add points to this point cloud.
Definition: point_cloud.cpp:400
rviz::PointCloud::depth_
float depth_
depth
Definition: point_cloud.h:229
rviz::PointCloud::setName
virtual void setName(const std::string &name)
Definition: point_cloud.h:208
rviz::PointCloud::render_mode_
RenderMode render_mode_
Definition: point_cloud.h:226
rviz::PointCloud::sphere_material_
Ogre::MaterialPtr sphere_material_
Definition: point_cloud.h:236
rviz::PointCloud::getWorldTransforms
virtual void getWorldTransforms(Ogre::Matrix4 *xform) const
Definition: point_cloud.cpp:159
rviz::PointCloudRenderable::getNumWorldTransforms
unsigned short getNumWorldTransforms() const override
Definition: point_cloud.h:81
rviz::PointCloud::visitRenderables
void visitRenderables(Ogre::Renderable::Visitor *visitor, bool debugRenderables) override
Definition: point_cloud.cpp:741
rviz::PointCloud::height_
float height_
height
Definition: point_cloud.h:228
rviz::PointCloud::pick_color_
Ogre::ColourValue pick_color_
Definition: point_cloud.h:247
rviz::PointCloud::bounding_box_
Ogre::AxisAlignedBox bounding_box_
The bounding box of this point cloud.
Definition: point_cloud.h:219
rviz::PointCloud::RM_POINTS
@ RM_POINTS
Definition: point_cloud.h:113
rviz::PointCloud::RM_SPHERES
@ RM_SPHERES
Definition: point_cloud.h:116
rviz::PointCloud::popPoints
void popPoints(uint32_t num_points)
Remove a number of points from this point cloud.
Definition: point_cloud.cpp:581
rviz::PointCloud::PointCloud
PointCloud()
Definition: point_cloud.cpp:92
rviz::PointCloudRenderable::PointCloudRenderable
PointCloudRenderable(PointCloud *parent, int num_points, bool use_tex_coords)
Definition: point_cloud.cpp:750
rviz::PointCloud::Point
Representation of a point, with x/y/z position and r/g/b color.
Definition: point_cloud.h:133
rviz::PointCloud::points_
V_Point points_
The list of points we're displaying. Allocates to a high-water-mark.
Definition: point_cloud.h:223
rviz::PointCloudRenderable::parent_
PointCloud * parent_
Definition: point_cloud.h:90
rviz::PointCloud::setAutoSize
void setAutoSize(bool auto_size)
Definition: point_cloud.cpp:316
rviz::PointCloud::RM_SQUARES
@ RM_SQUARES
Definition: point_cloud.h:114
rviz::PointCloudRenderable::getWorldTransforms
void getWorldTransforms(Ogre::Matrix4 *xform) const override
Definition: point_cloud.cpp:810
rviz::PointCloud::_notifyAttached
void _notifyAttached(Ogre::Node *parent, bool isTagPoint=false) override
Definition: point_cloud.cpp:658
rviz::PointCloud::sm_Type
static Ogre::String sm_Type
The "renderable type" used by Ogre.
Definition: point_cloud.h:249
rviz::PointCloud::Point::color
Ogre::ColourValue color
Definition: point_cloud.h:141
rviz
Definition: add_display_dialog.cpp:54
rviz::PointCloud::shrinkRenderables
void shrinkRenderables()
Definition: point_cloud.cpp:631
rviz::PointCloud::getBoundingRadius
float getBoundingRadius() const override
Definition: point_cloud.cpp:154
rviz::PointCloud::current_material_
Ogre::MaterialPtr current_material_
Definition: point_cloud.h:239
ogre_vector.h
rviz::PointCloud::box_material_
Ogre::MaterialPtr box_material_
Definition: point_cloud.h:238
rviz::PointCloud::current_mode_supports_geometry_shader_
bool current_mode_supports_geometry_shader_
Definition: point_cloud.h:246
rviz::PointCloud::Point::setColor
void setColor(float r, float g, float b, float a=1.0)
Definition: point_cloud.h:135
rviz::PointCloud::setPickColor
void setPickColor(const Ogre::ColourValue &color)
Definition: point_cloud.cpp:703
rviz::PointCloud::bounding_radius_
float bounding_radius_
The bounding radius of this point cloud.
Definition: point_cloud.h:220
rviz::PointCloud::~PointCloud
~PointCloud() override
Definition: point_cloud.cpp:137
rviz::PointCloud::tile_material_
Ogre::MaterialPtr tile_material_
Definition: point_cloud.h:237
rviz::PointCloudRenderablePtr
boost::shared_ptr< PointCloudRenderable > PointCloudRenderablePtr
Definition: point_cloud.h:92
rviz::PointCloud::setDimensions
void setDimensions(float width, float height, float depth)
Set the dimensions of the billboards used to render each point.
Definition: point_cloud.cpp:300
rviz::PointCloud::setRenderMode
void setRenderMode(RenderMode mode)
Set what type of rendering primitives should be used, currently points, billboards and boxes are supp...
Definition: point_cloud.cpp:218
rviz::PointCloudRenderable
Definition: point_cloud.h:64
rviz::PointCloudRenderable::getBoundingRadius
Ogre::Real getBoundingRadius() const override
Definition: point_cloud.cpp:794
rviz::PointCloud::getVerticesPerPoint
uint32_t getVerticesPerPoint()
Definition: point_cloud.cpp:663
rviz::PointCloud::RM_TILES
@ RM_TILES
Definition: point_cloud.h:117
rviz::PointCloud::color_by_index_
bool color_by_index_
Definition: point_cloud.h:242
rviz::PointCloud::point_material_
Ogre::MaterialPtr point_material_
Definition: point_cloud.h:233
rviz::PointCloud::alpha_
float alpha_
Definition: point_cloud.h:240
rviz::PointCloud::Point::position
Ogre::Vector3 position
Definition: point_cloud.h:140
rviz::PointCloudRenderable::material_
Ogre::MaterialPtr material_
Definition: point_cloud.h:89
rviz::PointCloud::common_up_vector_
Ogre::Vector3 common_up_vector_
See Ogre::BillboardSet::setCommonUpVector.
Definition: point_cloud.h:231
rviz::PointCloudRenderable::getBuffer
Ogre::HardwareVertexBufferSharedPtr getBuffer()
Definition: point_cloud.cpp:789
rviz::PointCloud::clear
void clear()
Clear all the points.
Definition: point_cloud.cpp:164
rviz::PointCloud::setColorByIndex
void setColorByIndex(bool set)
Definition: point_cloud.cpp:200
rviz::PointCloud::flat_square_material_
Ogre::MaterialPtr flat_square_material_
Definition: point_cloud.h:235
rviz::PointCloud::getMovableType
const Ogre::String & getMovableType() const override
Definition: point_cloud.h:193
rviz::PointCloud::RM_BOXES
@ RM_BOXES
Definition: point_cloud.h:118
rviz::PointCloudRenderable::getLights
const Ogre::LightList & getLights() const override
Definition: point_cloud.cpp:815
rviz::PointCloudRenderable::~PointCloudRenderable
~PointCloudRenderable() override
Definition: point_cloud.cpp:783
rviz::PointCloud::setHighlightColor
void setHighlightColor(float r, float g, float b)
Definition: point_cloud.cpp:206
rviz::PointCloud::createRenderable
PointCloudRenderablePtr createRenderable(int num_points)
Definition: point_cloud.cpp:717
rviz::PointCloud::getBoundingBox
const Ogre::AxisAlignedBox & getBoundingBox() const override
Definition: point_cloud.cpp:149
rviz::V_PointCloudRenderable
std::vector< PointCloudRenderablePtr > V_PointCloudRenderable
Definition: point_cloud.h:93
rviz::PointCloud::common_direction_
Ogre::Vector3 common_direction_
See Ogre::BillboardSet::setCommonDirection.
Definition: point_cloud.h:230
rviz::PointCloud::getNumWorldTransforms
virtual unsigned short getNumWorldTransforms() const
Definition: point_cloud.h:200
rviz::PointCloud::square_material_
Ogre::MaterialPtr square_material_
Definition: point_cloud.h:234
rviz::PointCloud::renderables_
V_PointCloudRenderable renderables_
Definition: point_cloud.h:244
rviz::PointCloud::_updateRenderQueue
void _updateRenderQueue(Ogre::RenderQueue *queue) override
Definition: point_cloud.cpp:648
rviz::PointCloud::setCommonDirection
void setCommonDirection(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonDirection.
Definition: point_cloud.cpp:326
rviz::PointCloud::setCommonUpVector
void setCommonUpVector(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonUpVector.
Definition: point_cloud.cpp:338
rviz::PointCloud::RenderMode
RenderMode
Definition: point_cloud.h:111
rviz::PointCloud::V_Point
std::vector< Point > V_Point
Definition: point_cloud.h:222
rviz::PointCloud::RM_FLAT_SQUARES
@ RM_FLAT_SQUARES
Definition: point_cloud.h:115
rviz::PointCloudRenderable::getSquaredViewDepth
Ogre::Real getSquaredViewDepth(const Ogre::Camera *cam) const override
Definition: point_cloud.cpp:799


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10