point_cloud.cpp
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 #include "point_cloud.h"
31 #include <ros/assert.h>
32 #include <qglobal.h>
33 
34 #include <OgreSceneManager.h>
35 #include <OgreSceneNode.h>
36 #include <OgreVector3.h>
37 #include <OgreQuaternion.h>
38 #include <OgreManualObject.h>
39 #include <OgreMaterialManager.h>
40 #include <OgreBillboard.h>
41 #include <OgreTexture.h>
42 #include <OgreTextureManager.h>
43 #include <OgreSharedPtr.h>
44 #include <OgreTechnique.h>
45 #include <OgreCamera.h>
46 
47 #include <sstream>
48 
51 
52 #define VERTEX_BUFFER_CAPACITY (36 * 1024 * 10)
53 
54 namespace rviz
55 {
56 static float g_point_vertices[3] = {0.0f, 0.0f, 0.0f};
57 
58 static float g_billboard_vertices[6 * 3] = {
59  -0.5f, 0.5f, 0.0f, -0.5f, -0.5f, 0.0f, 0.5f, 0.5f, 0.0f,
60  0.5f, 0.5f, 0.0f, -0.5f, -0.5f, 0.0f, 0.5f, -0.5f, 0.0f,
61 };
62 
63 static float g_billboard_sphere_vertices[3 * 3] = {
64  0.0f, 1.0f, 0.0f, -0.866025404f, -0.5f, 0.0f, 0.866025404f, -0.5f, 0.0f,
65 };
66 
67 static float g_box_vertices[6 * 6 * 3] = {
68  // clang-format off
69  // front
70  -0.5f, 0.5f, -0.5f, -0.5f, -0.5f, -0.5f, 0.5f, 0.5f, -0.5f, 0.5f, 0.5f, -0.5f, -0.5f, -0.5f, -0.5f,
71  0.5f, -0.5f, -0.5f,
72 
73  // back
74  -0.5f, 0.5f, 0.5f, 0.5f, 0.5f, 0.5f, -0.5f, -0.5f, 0.5f, 0.5f, 0.5f, 0.5f, 0.5f, -0.5f, 0.5f, -0.5f,
75  -0.5f, 0.5f,
76 
77  // right
78  0.5, 0.5, 0.5, 0.5, 0.5, -0.5, 0.5, -0.5, 0.5, 0.5, 0.5, -0.5, 0.5, -0.5, -0.5, 0.5, -0.5, 0.5,
79 
80  // left
81  -0.5, 0.5, 0.5, -0.5, -0.5, 0.5, -0.5, 0.5, -0.5, -0.5, 0.5, -0.5, -0.5, -0.5, 0.5, -0.5, -0.5, -0.5,
82 
83  // top
84  -0.5, 0.5, -0.5, 0.5, 0.5, -0.5, -0.5, 0.5, 0.5, 0.5, 0.5, -0.5, 0.5, 0.5, 0.5, -0.5, 0.5, 0.5,
85 
86  // bottom
87  -0.5, -0.5, -0.5, -0.5, -0.5, 0.5, 0.5, -0.5, -0.5, 0.5, -0.5, -0.5, -0.5, -0.5, 0.5, 0.5, -0.5, 0.5,
88 }; // clang-format on
89 
90 Ogre::String PointCloud::sm_Type = "PointCloud";
91 
93  : bounding_radius_(0.0f)
94  , point_count_(0)
95  , common_direction_(Ogre::Vector3::NEGATIVE_UNIT_Z)
96  , common_up_vector_(Ogre::Vector3::UNIT_Y)
97  , color_by_index_(false)
98  , current_mode_supports_geometry_shader_(false)
99 {
100  std::stringstream ss;
101  static int count = 0;
102  ss << "PointCloudMaterial" << count++;
103  point_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudPoint");
104  square_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudSquare");
105  flat_square_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudFlatSquare");
106  sphere_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudSphere");
107  tile_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudTile");
108  box_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/PointCloudBox");
109 
110  point_material_ = Ogre::MaterialPtr(point_material_)->clone(ss.str() + "Point");
111  square_material_ = Ogre::MaterialPtr(square_material_)->clone(ss.str() + "Square");
112  flat_square_material_ = Ogre::MaterialPtr(flat_square_material_)->clone(ss.str() + "FlatSquare");
113  sphere_material_ = Ogre::MaterialPtr(sphere_material_)->clone(ss.str() + "Sphere");
114  tile_material_ = Ogre::MaterialPtr(tile_material_)->clone(ss.str() + "Tiles");
115  box_material_ = Ogre::MaterialPtr(box_material_)->clone(ss.str() + "Box");
116 
117  point_material_->load();
118  square_material_->load();
119  flat_square_material_->load();
120  sphere_material_->load();
121  tile_material_->load();
122  box_material_->load();
123 
124  setAlpha(1.0f);
126  setDimensions(0.01f, 0.01f, 0.01f);
127 
128  clear();
129 }
130 
131 static void removeMaterial(Ogre::MaterialPtr& material)
132 {
133  Ogre::ResourcePtr resource(material);
134  Ogre::MaterialManager::getSingleton().remove(resource);
135 }
136 
138 {
139  clear();
140 
141  point_material_->unload();
142  square_material_->unload();
143  flat_square_material_->unload();
144  sphere_material_->unload();
145  tile_material_->unload();
146  box_material_->unload();
147 
154 }
155 
156 const Ogre::AxisAlignedBox& PointCloud::getBoundingBox() const
157 {
158  return bounding_box_;
159 }
160 
162 {
163  return bounding_radius_;
164 }
165 
166 void PointCloud::getWorldTransforms(Ogre::Matrix4* xform) const
167 {
168  *xform = _getParentNodeFullTransform();
169 }
170 
172 {
173  point_count_ = 0;
174  bounding_box_.setNull();
175  bounding_radius_ = 0.0f;
176 
177  if (getParentSceneNode())
178  {
179  V_PointCloudRenderable::iterator it = renderables_.begin();
180  V_PointCloudRenderable::iterator end = renderables_.end();
181  for (; it != end; ++it)
182  {
183  getParentSceneNode()->detachObject(it->get());
184  }
185  getParentSceneNode()->needUpdate();
186  }
187 
188  renderables_.clear();
189 }
190 
192 {
193  if (point_count_ == 0)
194  {
195  return;
196  }
197 
198  V_Point points;
199  points.swap(points_);
200  uint32_t count = point_count_;
201 
202  clear();
203 
204  addPoints(&points.front(), count);
205 }
206 
208 {
209  color_by_index_ = set;
210  regenerateAll();
211 }
212 
213 void PointCloud::setHighlightColor(float r, float g, float b)
214 {
215  Ogre::Vector4 highlight(r, g, b, 0.0f);
216 
217  V_PointCloudRenderable::iterator it = renderables_.begin();
218  V_PointCloudRenderable::iterator end = renderables_.end();
219  for (; it != end; ++it)
220  {
221  (*it)->setCustomParameter(HIGHLIGHT_PARAMETER, highlight);
222  }
223 }
224 
226 {
227  render_mode_ = mode;
228 
229  if (mode == RM_POINTS)
230  {
231  current_material_ = Ogre::MaterialPtr(point_material_);
232  }
233  else if (mode == RM_SQUARES)
234  {
235  current_material_ = Ogre::MaterialPtr(square_material_);
236  }
237  else if (mode == RM_FLAT_SQUARES)
238  {
239  current_material_ = Ogre::MaterialPtr(flat_square_material_);
240  }
241  else if (mode == RM_SPHERES)
242  {
243  current_material_ = Ogre::MaterialPtr(sphere_material_);
244  }
245  else if (mode == RM_TILES)
246  {
247  current_material_ = Ogre::MaterialPtr(tile_material_);
248  }
249  else if (mode == RM_BOXES)
250  {
251  current_material_ = Ogre::MaterialPtr(box_material_);
252  }
253 
254  current_material_->load();
255 
256  // ROS_INFO("Best technique [%s] [gp=%s]", current_material_->getBestTechnique()->getName().c_str(),
257  // current_material_->getBestTechnique()->getPass(0)->getGeometryProgramName().c_str());
258 
259  bool geom_support_changed = false;
260  Ogre::Technique* best = current_material_->getBestTechnique();
261  if (best)
262  {
263  if (current_material_->getBestTechnique()->getName() == "gp")
264  {
266  {
267  geom_support_changed = true;
268  }
269 
271 
272  // ROS_INFO("Using geometry shader");
273  }
274  else
275  {
277  {
278  geom_support_changed = true;
279  }
280 
282  }
283  }
284  else
285  {
286  geom_support_changed = true;
288 
289  ROS_ERROR("No techniques available for material [%s]", current_material_->getName().c_str());
290  }
291 
292  if (geom_support_changed)
293  {
294  renderables_.clear();
295  }
296 
297  V_PointCloudRenderable::iterator it = renderables_.begin();
298  V_PointCloudRenderable::iterator end = renderables_.end();
299  for (; it != end; ++it)
300  {
301  (*it)->setMaterial(current_material_->getName());
302  }
303 
304  regenerateAll();
305 }
306 
307 void PointCloud::setDimensions(float width, float height, float depth)
308 {
309  width_ = width;
310  height_ = height;
311  depth_ = depth;
312 
313  Ogre::Vector4 size(width_, height_, depth_, 0.0f);
314 
315  V_PointCloudRenderable::iterator it = renderables_.begin();
316  V_PointCloudRenderable::iterator end = renderables_.end();
317  for (; it != end; ++it)
318  {
319  (*it)->setCustomParameter(SIZE_PARAMETER, size);
320  }
321 }
322 
323 void PointCloud::setAutoSize(bool auto_size)
324 {
325  V_PointCloudRenderable::iterator it = renderables_.begin();
326  V_PointCloudRenderable::iterator end = renderables_.end();
327  for (; it != end; ++it)
328  {
329  (*it)->setCustomParameter(AUTO_SIZE_PARAMETER, Ogre::Vector4(auto_size));
330  }
331 }
332 
333 void PointCloud::setCommonDirection(const Ogre::Vector3& vec)
334 {
335  common_direction_ = vec;
336 
337  V_PointCloudRenderable::iterator it = renderables_.begin();
338  V_PointCloudRenderable::iterator end = renderables_.end();
339  for (; it != end; ++it)
340  {
341  (*it)->setCustomParameter(NORMAL_PARAMETER, Ogre::Vector4(vec));
342  }
343 }
344 
345 void PointCloud::setCommonUpVector(const Ogre::Vector3& vec)
346 {
347  common_up_vector_ = vec;
348 
349  V_PointCloudRenderable::iterator it = renderables_.begin();
350  V_PointCloudRenderable::iterator end = renderables_.end();
351  for (; it != end; ++it)
352  {
353  (*it)->setCustomParameter(UP_PARAMETER, Ogre::Vector4(vec));
354  }
355 }
356 
357 void setAlphaBlending(const Ogre::MaterialPtr& mat)
358 {
359  if (mat->getBestTechnique())
360  {
361  mat->getBestTechnique()->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
362  mat->getBestTechnique()->setDepthWriteEnabled(false);
363  }
364 }
365 
366 void setReplace(const Ogre::MaterialPtr& mat)
367 {
368  if (mat->getBestTechnique())
369  {
370  mat->getBestTechnique()->setSceneBlending(Ogre::SBT_REPLACE);
371  mat->getBestTechnique()->setDepthWriteEnabled(true);
372  }
373 }
374 
375 void PointCloud::setAlpha(float alpha, bool per_point_alpha)
376 {
377  alpha_ = alpha;
378 
379  if (alpha < 0.9998 || per_point_alpha)
380  {
387  }
388  else
389  {
396  }
397 
398  Ogre::Vector4 alpha4(alpha_, alpha_, alpha_, alpha_);
399  V_PointCloudRenderable::iterator it = renderables_.begin();
400  V_PointCloudRenderable::iterator end = renderables_.end();
401  for (; it != end; ++it)
402  {
403  (*it)->setCustomParameter(ALPHA_PARAMETER, alpha4);
404  }
405 }
406 
407 void PointCloud::addPoints(Point* points, uint32_t num_points)
408 {
409  if (num_points == 0)
410  {
411  return;
412  }
413  Ogre::Root* root = Ogre::Root::getSingletonPtr();
414 
415  if (points_.size() < point_count_ + num_points)
416  {
417  points_.resize(point_count_ + num_points);
418  }
419 
420  Point* begin = &points_.front() + point_count_;
421  memcpy(begin, points, sizeof(Point) * num_points);
422 
423  uint32_t vpp = getVerticesPerPoint();
424  Ogre::RenderOperation::OperationType op_type;
426  {
427  op_type = Ogre::RenderOperation::OT_POINT_LIST;
428  }
429  else
430  {
431  if (render_mode_ == RM_POINTS)
432  {
433  op_type = Ogre::RenderOperation::OT_POINT_LIST;
434  }
435  else
436  {
437  op_type = Ogre::RenderOperation::OT_TRIANGLE_LIST;
438  }
439  }
440 
441  float* vertices = nullptr;
443  {
444  vertices = g_point_vertices;
445  }
446  else
447  {
448  if (render_mode_ == RM_POINTS)
449  {
450  vertices = g_point_vertices;
451  }
452  else if (render_mode_ == RM_SQUARES)
453  {
454  vertices = g_billboard_vertices;
455  }
456  else if (render_mode_ == RM_FLAT_SQUARES)
457  {
458  vertices = g_billboard_vertices;
459  }
460  else if (render_mode_ == RM_SPHERES)
461  {
462  vertices = g_billboard_sphere_vertices;
463  }
464  else if (render_mode_ == RM_TILES)
465  {
466  vertices = g_billboard_vertices;
467  }
468  else if (render_mode_ == RM_BOXES)
469  {
470  vertices = g_box_vertices;
471  }
472  }
473 
475  Ogre::HardwareVertexBufferSharedPtr vbuf;
476  void* vdata = nullptr;
477  Ogre::RenderOperation* op = nullptr;
478  float* fptr = nullptr;
479 
480  Ogre::AxisAlignedBox aabb;
481  aabb.setNull();
482  uint32_t current_vertex_count = 0;
483  bounding_radius_ = 0.0f;
484  uint32_t vertex_size = 0;
485  uint32_t buffer_size = 0;
486  for (uint32_t current_point = 0; current_point < num_points; ++current_point)
487  {
488  // if we didn't create a renderable yet,
489  // or we've reached the vertex limit for the current renderable,
490  // create a new one.
491  while (!rend || current_vertex_count >= buffer_size)
492  {
493  if (rend)
494  {
495  ROS_ASSERT(current_vertex_count == buffer_size);
496 
497  op->vertexData->vertexCount = rend->getBuffer()->getNumVertices() - op->vertexData->vertexStart;
498  ROS_ASSERT(op->vertexData->vertexCount + op->vertexData->vertexStart <=
499  rend->getBuffer()->getNumVertices());
500  vbuf->unlock();
501  rend->setBoundingBox(aabb);
502  bounding_box_.merge(aabb);
503  }
504 
505  buffer_size = std::min<int>(VERTEX_BUFFER_CAPACITY, (num_points - current_point) * vpp);
506 
507  rend = createRenderable(buffer_size);
508  vbuf = rend->getBuffer();
509  vdata = vbuf->lock(Ogre::HardwareBuffer::HBL_NO_OVERWRITE);
510 
511  op = rend->getRenderOperation();
512  op->operationType = op_type;
513  current_vertex_count = 0;
514 
515  vertex_size = op->vertexData->vertexDeclaration->getVertexSize(0);
516  fptr = (float*)((uint8_t*)vdata);
517 
518  aabb.setNull();
519  }
520 
521  const Point& p = points[current_point];
522 
523  uint32_t color;
524 
525  if (color_by_index_)
526  {
527  // convert to ColourValue, so we can then convert to the rendersystem-specific color type
528  color = (current_point + point_count_ + 1);
529  Ogre::ColourValue c;
530  c.a = 1.0f;
531  c.r = ((color >> 16) & 0xff) / 255.0f;
532  c.g = ((color >> 8) & 0xff) / 255.0f;
533  c.b = (color & 0xff) / 255.0f;
534  root->convertColourValue(c, &color);
535  }
536  else
537  {
538  root->convertColourValue(p.color, &color);
539  }
540 
541  aabb.merge(p.position);
542  bounding_radius_ = std::max(bounding_radius_, p.position.squaredLength());
543 
544  float x = p.position.x;
545  float y = p.position.y;
546  float z = p.position.z;
547 
548  for (uint32_t j = 0; j < vpp; ++j, ++current_vertex_count)
549  {
550  *fptr++ = x;
551  *fptr++ = y;
552  *fptr++ = z;
553 
555  {
556  *fptr++ = vertices[(j * 3)];
557  *fptr++ = vertices[(j * 3) + 1];
558  *fptr++ = vertices[(j * 3) + 2];
559  }
560 
561  uint32_t* iptr = (uint32_t*)fptr;
562  *iptr = color;
563  ++fptr;
564 
565  ROS_ASSERT((uint8_t*)fptr <= (uint8_t*)vdata + rend->getBuffer()->getNumVertices() * vertex_size);
566  Q_UNUSED(vertex_size);
567  }
568  }
569 
570  op->vertexData->vertexCount = current_vertex_count - op->vertexData->vertexStart;
571  rend->setBoundingBox(aabb);
572  bounding_box_.merge(aabb);
573  ROS_ASSERT(op->vertexData->vertexCount + op->vertexData->vertexStart <=
574  rend->getBuffer()->getNumVertices());
575 
576  vbuf->unlock();
577 
578  point_count_ += num_points;
579 
581 
582  if (getParentSceneNode())
583  {
584  getParentSceneNode()->needUpdate();
585  }
586 }
587 
588 void PointCloud::popPoints(uint32_t num_points)
589 {
590  uint32_t vpp = getVerticesPerPoint();
591 
592  ROS_ASSERT(num_points <= point_count_);
593  points_.erase(points_.begin(), points_.begin() + num_points);
594 
595  point_count_ -= num_points;
596 
597  // Now clear out popped points
598  uint32_t popped_count = 0;
599  while (popped_count < num_points * vpp)
600  {
601  PointCloudRenderablePtr rend = renderables_.front();
602  Ogre::RenderOperation* op = rend->getRenderOperation();
603 
604  uint32_t popped = std::min((size_t)(num_points * vpp - popped_count), op->vertexData->vertexCount);
605  op->vertexData->vertexStart += popped;
606  op->vertexData->vertexCount -= popped;
607 
608  popped_count += popped;
609 
610  if (op->vertexData->vertexCount == 0)
611  {
612  renderables_.erase(renderables_.begin(), renderables_.begin() + 1);
613 
614  op->vertexData->vertexStart = 0;
615  renderables_.push_back(rend);
616  }
617  }
618  ROS_ASSERT(popped_count == num_points * vpp);
619 
620  // reset bounds
621  bounding_box_.setNull();
622  bounding_radius_ = 0.0f;
623  for (uint32_t i = 0; i < point_count_; ++i)
624  {
625  Point& p = points_[i];
626  bounding_box_.merge(p.position);
627  bounding_radius_ = std::max(bounding_radius_, p.position.squaredLength());
628  }
629 
631 
632  if (getParentSceneNode())
633  {
634  getParentSceneNode()->needUpdate();
635  }
636 }
637 
639 {
640  while (!renderables_.empty())
641  {
643  Ogre::RenderOperation* op = rend->getRenderOperation();
644  if (op->vertexData->vertexCount == 0)
645  {
646  renderables_.pop_back();
647  }
648  else
649  {
650  break;
651  }
652  }
653 }
654 
655 void PointCloud::_notifyCurrentCamera(Ogre::Camera* camera)
656 {
657  MovableObject::_notifyCurrentCamera(camera);
658 }
659 
660 void PointCloud::_updateRenderQueue(Ogre::RenderQueue* queue)
661 {
662  V_PointCloudRenderable::iterator it = renderables_.begin();
663  V_PointCloudRenderable::iterator end = renderables_.end();
664  for (; it != end; ++it)
665  {
666  queue->addRenderable((*it).get());
667  }
668 }
669 
670 void PointCloud::_notifyAttached(Ogre::Node* parent, bool isTagPoint)
671 {
672  MovableObject::_notifyAttached(parent, isTagPoint);
673 }
674 
676 {
678  {
679  return 1;
680  }
681 
682  if (render_mode_ == RM_POINTS)
683  {
684  return 1;
685  }
686 
687  if (render_mode_ == RM_SQUARES)
688  {
689  return 6;
690  }
691 
693  {
694  return 6;
695  }
696 
697  if (render_mode_ == RM_TILES)
698  {
699  return 6;
700  }
701 
702  if (render_mode_ == RM_SPHERES)
703  {
704  return 3;
705  }
706 
707  if (render_mode_ == RM_BOXES)
708  {
709  return 36;
710  }
711 
712  return 1;
713 }
714 
715 void PointCloud::setPickColor(const Ogre::ColourValue& color)
716 {
717  pick_color_ = color;
718  Ogre::Vector4 pick_col(pick_color_.r, pick_color_.g, pick_color_.b, pick_color_.a);
719 
720  V_PointCloudRenderable::iterator it = renderables_.begin();
721  V_PointCloudRenderable::iterator end = renderables_.end();
722  for (; it != end; ++it)
723  {
724  (*it)->setCustomParameter(PICK_COLOR_PARAMETER, pick_col);
725  }
726  getUserObjectBindings().setUserAny("pick_handle", Ogre::Any(colorToHandle(color)));
727 }
728 
730 {
733  rend->setMaterial(current_material_->getName());
734  Ogre::Vector4 size(width_, height_, depth_, 0.0f);
735  Ogre::Vector4 alpha(alpha_, 0.0f, 0.0f, 0.0f);
736  Ogre::Vector4 highlight(0.0f, 0.0f, 0.0f, 0.0f);
737  Ogre::Vector4 pick_col(pick_color_.r, pick_color_.g, pick_color_.b, pick_color_.a);
738  rend->setCustomParameter(SIZE_PARAMETER, size);
739  rend->setCustomParameter(ALPHA_PARAMETER, alpha);
740  rend->setCustomParameter(HIGHLIGHT_PARAMETER, highlight);
741  rend->setCustomParameter(PICK_COLOR_PARAMETER, pick_col);
742  rend->setCustomParameter(NORMAL_PARAMETER, Ogre::Vector4(common_direction_));
743  rend->setCustomParameter(UP_PARAMETER, Ogre::Vector4(common_up_vector_));
744  if (getParentSceneNode())
745  {
746  getParentSceneNode()->attachObject(rend.get());
747  }
748  renderables_.push_back(rend);
749 
750  return rend;
751 }
752 
753 #if (OGRE_VERSION_MAJOR >= 1 && OGRE_VERSION_MINOR >= 6)
754 void PointCloud::visitRenderables(Ogre::Renderable::Visitor* /*visitor*/, bool /*debugRenderables*/)
755 {
756 }
757 #endif
758 
759 
763 
764 PointCloudRenderable::PointCloudRenderable(PointCloud* parent, int num_points, bool use_tex_coords)
765  : parent_(parent)
766 {
767  // Initialize render operation
768  mRenderOp.operationType = Ogre::RenderOperation::OT_POINT_LIST;
769  mRenderOp.useIndexes = false;
770  mRenderOp.vertexData = new Ogre::VertexData;
771  mRenderOp.vertexData->vertexStart = 0;
772  mRenderOp.vertexData->vertexCount = 0;
773 
774  Ogre::VertexDeclaration* decl = mRenderOp.vertexData->vertexDeclaration;
775  size_t offset = 0;
776 
777  decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_POSITION);
778  offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
779 
780  if (use_tex_coords)
781  {
782  decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_TEXTURE_COORDINATES, 0);
783  offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
784  }
785 
786  decl->addElement(0, offset, Ogre::VET_COLOUR, Ogre::VES_DIFFUSE);
787 
788  Ogre::HardwareVertexBufferSharedPtr vbuf =
789  Ogre::HardwareBufferManager::getSingleton().createVertexBuffer(
790  mRenderOp.vertexData->vertexDeclaration->getVertexSize(0), num_points,
791  Ogre::HardwareBuffer::HBU_DYNAMIC);
792 
793  // Bind buffer
794  mRenderOp.vertexData->vertexBufferBinding->setBinding(0, vbuf);
795 }
796 
798 {
799  delete mRenderOp.vertexData;
800  delete mRenderOp.indexData;
801 }
802 
803 Ogre::HardwareVertexBufferSharedPtr PointCloudRenderable::getBuffer()
804 {
805  return mRenderOp.vertexData->vertexBufferBinding->getBuffer(0);
806 }
807 
809 {
810  SimpleRenderable::_notifyCurrentCamera(camera);
811 }
812 
814 {
815  return Ogre::Math::Sqrt(std::max(mBox.getMaximum().squaredLength(), mBox.getMinimum().squaredLength()));
816 }
817 
818 Ogre::Real PointCloudRenderable::getSquaredViewDepth(const Ogre::Camera* cam) const
819 {
820  Ogre::Vector3 vMin, vMax, vMid, vDist;
821  vMin = mBox.getMinimum();
822  vMax = mBox.getMaximum();
823  vMid = ((vMax - vMin) * 0.5) + vMin;
824  vDist = cam->getDerivedPosition() - vMid;
825 
826  return vDist.squaredLength();
827 }
828 
829 void PointCloudRenderable::getWorldTransforms(Ogre::Matrix4* xform) const
830 {
831  parent_->getWorldTransforms(xform);
832 }
833 
834 const Ogre::LightList& PointCloudRenderable::getLights() const
835 {
836  return parent_->queryLights();
837 }
838 
839 } // namespace rviz
#define ALPHA_PARAMETER
void addPoints(Point *points, uint32_t num_points)
Add points to this point cloud.
float width_
width
Definition: point_cloud.h:229
Ogre::MaterialPtr current_material_
Definition: point_cloud.h:241
root
Ogre::MaterialPtr sphere_material_
Definition: point_cloud.h:238
std::vector< Point > V_Point
Definition: point_cloud.h:224
void setAlphaBlending(const Ogre::MaterialPtr &mat)
Ogre::Real getBoundingRadius() const override
~PointCloud() override
void setRenderMode(RenderMode mode)
Set what type of rendering primitives should be used, currently points, billboards and boxes are supp...
f
#define AUTO_SIZE_PARAMETER
uint32_t point_count_
The number of points currently in points_.
Definition: point_cloud.h:226
void setPickColor(const Ogre::ColourValue &color)
Ogre::HardwareVertexBufferSharedPtr getBuffer()
#define NORMAL_PARAMETER
static float g_box_vertices[6 *6 *3]
Definition: point_cloud.cpp:67
void setColorByIndex(bool set)
const Ogre::LightList & getLights() const override
Ogre::AxisAlignedBox bounding_box_
The bounding box of this point cloud.
Definition: point_cloud.h:221
Ogre::MaterialPtr flat_square_material_
Definition: point_cloud.h:237
void popPoints(uint32_t num_points)
Remove a number of points from this point cloud.
float depth_
depth
Definition: point_cloud.h:231
V_Point points_
The list of points we&#39;re displaying. Allocates to a high-water-mark.
Definition: point_cloud.h:225
virtual void getWorldTransforms(Ogre::Matrix4 *xform) const
Ogre::MaterialPtr square_material_
Definition: point_cloud.h:236
Ogre::Vector3 common_direction_
See Ogre::BillboardSet::setCommonDirection.
Definition: point_cloud.h:232
void _notifyCurrentCamera(Ogre::Camera *camera) override
#define SIZE_PARAMETER
#define VERTEX_BUFFER_CAPACITY
Definition: point_cloud.cpp:52
void setCommonUpVector(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonUpVector.
Ogre::Real getSquaredViewDepth(const Ogre::Camera *cam) const override
bool current_mode_supports_geometry_shader_
Definition: point_cloud.h:248
Ogre::MaterialPtr tile_material_
Definition: point_cloud.h:239
#define HIGHLIGHT_PARAMETER
Representation of a point, with x/y/z position and r/g/b color.
Definition: point_cloud.h:132
void setDimensions(float width, float height, float depth)
Set the dimensions of the billboards used to render each point.
Ogre::Vector3 position
Definition: point_cloud.h:139
RenderMode render_mode_
Definition: point_cloud.h:228
void setAlpha(float alpha, bool per_point_alpha=false)
void clear()
Clear all the points.
Ogre::MaterialPtr box_material_
Definition: point_cloud.h:240
void _notifyCurrentCamera(Ogre::Camera *camera) override
#define PICK_COLOR_PARAMETER
float bounding_radius_
The bounding radius of this point cloud.
Definition: point_cloud.h:222
void setReplace(const Ogre::MaterialPtr &mat)
static void removeMaterial(Ogre::MaterialPtr &material)
uint32_t colorToHandle(Ogre::PixelFormat fmt, uint32_t col)
Definition: forwards.h:66
static float g_billboard_vertices[6 *3]
Definition: point_cloud.cpp:58
const Ogre::AxisAlignedBox & getBoundingBox() const override
Ogre::ColourValue color
Definition: point_cloud.h:140
Ogre::ColourValue pick_color_
Definition: point_cloud.h:249
uint32_t getVerticesPerPoint()
void setHighlightColor(float r, float g, float b)
A visual representation of a set of points.
Definition: point_cloud.h:107
V_PointCloudRenderable renderables_
Definition: point_cloud.h:246
PointCloudRenderable(PointCloud *parent, int num_points, bool use_tex_coords)
Ogre::MaterialPtr point_material_
Definition: point_cloud.h:235
float height_
height
Definition: point_cloud.h:230
void setCommonDirection(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonDirection.
Ogre::Vector3 common_up_vector_
See Ogre::BillboardSet::setCommonUpVector.
Definition: point_cloud.h:233
static float g_point_vertices[3]
Definition: point_cloud.cpp:56
void _notifyAttached(Ogre::Node *parent, bool isTagPoint=false) override
#define ROS_ASSERT(cond)
static float g_billboard_sphere_vertices[3 *3]
Definition: point_cloud.cpp:63
void _updateRenderQueue(Ogre::RenderQueue *queue) override
#define ROS_ERROR(...)
static Ogre::String sm_Type
The "renderable type" used by Ogre.
Definition: point_cloud.h:251
void setAutoSize(bool auto_size)
float getBoundingRadius() const override
PointCloudRenderablePtr createRenderable(int num_points)
void getWorldTransforms(Ogre::Matrix4 *xform) const override
#define UP_PARAMETER
void shrinkRenderables()


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25