34 #include <OgreSceneManager.h>
35 #include <OgreSceneNode.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>
53 #define VERTEX_BUFFER_CAPACITY (36 * 1024 * 10)
60 -0.5f, 0.5f, 0.0f, -0.5f, -0.5f, 0.0f, 0.5f, 0.5f, 0.0f,
61 0.5f, 0.5f, 0.0f, -0.5f, -0.5f, 0.0f, 0.5f, -0.5f, 0.0f,
65 0.0f, 1.0f, 0.0f, -0.866025404f, -0.5f, 0.0f, 0.866025404f, -0.5f, 0.0f,
71 -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, 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,
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,
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,
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,
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,
93 : bounding_radius_(0.0
f)
97 , color_by_index_(false)
98 , current_mode_supports_geometry_shader_(false)
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");
133 Ogre::ResourcePtr resource(material);
134 Ogre::MaterialManager::getSingleton().remove(resource);
161 *xform = _getParentNodeFullTransform();
170 if (getParentSceneNode())
172 V_PointCloudRenderable::iterator it =
renderables_.begin();
173 V_PointCloudRenderable::iterator end =
renderables_.end();
174 for (; it != end; ++it)
176 getParentSceneNode()->detachObject(it->get());
178 getParentSceneNode()->needUpdate();
208 Ogre::Vector4 highlight(r, g, b, 0.0
f);
210 V_PointCloudRenderable::iterator it =
renderables_.begin();
211 V_PointCloudRenderable::iterator end =
renderables_.end();
212 for (; it != end; ++it)
252 bool geom_support_changed =
false;
260 geom_support_changed =
true;
271 geom_support_changed =
true;
279 geom_support_changed =
true;
285 if (geom_support_changed)
290 V_PointCloudRenderable::iterator it =
renderables_.begin();
291 V_PointCloudRenderable::iterator end =
renderables_.end();
292 for (; it != end; ++it)
308 V_PointCloudRenderable::iterator it =
renderables_.begin();
309 V_PointCloudRenderable::iterator end =
renderables_.end();
310 for (; it != end; ++it)
318 V_PointCloudRenderable::iterator it =
renderables_.begin();
319 V_PointCloudRenderable::iterator end =
renderables_.end();
320 for (; it != end; ++it)
330 V_PointCloudRenderable::iterator it =
renderables_.begin();
331 V_PointCloudRenderable::iterator end =
renderables_.end();
332 for (; it != end; ++it)
342 V_PointCloudRenderable::iterator it =
renderables_.begin();
343 V_PointCloudRenderable::iterator end =
renderables_.end();
344 for (; it != end; ++it)
346 (*it)->setCustomParameter(
UP_PARAMETER, Ogre::Vector4(vec));
352 if (mat->getBestTechnique())
354 mat->getBestTechnique()->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
355 mat->getBestTechnique()->setDepthWriteEnabled(
false);
361 if (mat->getBestTechnique())
363 mat->getBestTechnique()->setSceneBlending(Ogre::SBT_REPLACE);
364 mat->getBestTechnique()->setDepthWriteEnabled(
true);
372 if (alpha < 0.9998 || per_point_alpha)
392 V_PointCloudRenderable::iterator it =
renderables_.begin();
393 V_PointCloudRenderable::iterator end =
renderables_.end();
394 for (; it != end; ++it)
406 Ogre::Root*
root = Ogre::Root::getSingletonPtr();
414 #if defined(__GNUC__) && (__GNUC__ >= 8)
415 #pragma GCC diagnostic push
416 #pragma GCC diagnostic ignored "-Wclass-memaccess"
418 memcpy(begin, points,
sizeof(
Point) * num_points);
419 #if defined(__GNUC__) && (__GNUC__ >= 8)
420 #pragma GCC diagnostic pop
424 Ogre::RenderOperation::OperationType op_type;
427 op_type = Ogre::RenderOperation::OT_POINT_LIST;
433 op_type = Ogre::RenderOperation::OT_POINT_LIST;
437 op_type = Ogre::RenderOperation::OT_TRIANGLE_LIST;
441 float* vertices =
nullptr;
468 Ogre::HardwareVertexBufferSharedPtr vbuf;
469 void* vdata =
nullptr;
470 Ogre::RenderOperation* op =
nullptr;
471 float* fptr =
nullptr;
473 Ogre::AxisAlignedBox aabb;
475 uint32_t current_vertex_count = 0;
477 uint32_t vertex_size = 0;
478 uint32_t buffer_size = 0;
479 for (uint32_t current_point = 0; current_point < num_points; ++current_point)
484 while (!rend || current_vertex_count >= buffer_size)
488 ROS_ASSERT(current_vertex_count == buffer_size);
490 op->vertexData->vertexCount = rend->getBuffer()->getNumVertices() - op->vertexData->vertexStart;
491 ROS_ASSERT(op->vertexData->vertexCount + op->vertexData->vertexStart <=
492 rend->getBuffer()->getNumVertices());
494 rend->setBoundingBox(aabb);
501 vbuf = rend->getBuffer();
502 vdata = vbuf->lock(Ogre::HardwareBuffer::HBL_NO_OVERWRITE);
504 op = rend->getRenderOperation();
505 op->operationType = op_type;
506 current_vertex_count = 0;
508 vertex_size = op->vertexData->vertexDeclaration->getVertexSize(0);
509 fptr = (
float*)((uint8_t*)vdata);
514 const Point& p = points[current_point];
524 c.r = ((color >> 16) & 0xff) / 255.0f;
525 c.g = ((color >> 8) & 0xff) / 255.0f;
526 c.b = (color & 0xff) / 255.0
f;
527 root->convertColourValue(c, &color);
531 root->convertColourValue(p.
color, &color);
541 for (uint32_t j = 0; j < vpp; ++j, ++current_vertex_count)
549 *fptr++ = vertices[(j * 3)];
550 *fptr++ = vertices[(j * 3) + 1];
551 *fptr++ = vertices[(j * 3) + 2];
554 uint32_t* iptr = (uint32_t*)fptr;
558 ROS_ASSERT((uint8_t*)fptr <= (uint8_t*)vdata + rend->getBuffer()->getNumVertices() * vertex_size);
559 Q_UNUSED(vertex_size);
563 op->vertexData->vertexCount = current_vertex_count - op->vertexData->vertexStart;
564 rend->setBoundingBox(aabb);
566 ROS_ASSERT(op->vertexData->vertexCount + op->vertexData->vertexStart <=
567 rend->getBuffer()->getNumVertices());
575 if (getParentSceneNode())
577 getParentSceneNode()->needUpdate();
591 uint32_t popped_count = 0;
592 while (popped_count < num_points * vpp)
595 Ogre::RenderOperation* op = rend->getRenderOperation();
597 uint32_t popped = std::min((
size_t)(num_points * vpp - popped_count), op->vertexData->vertexCount);
598 op->vertexData->vertexStart += popped;
599 op->vertexData->vertexCount -= popped;
601 popped_count += popped;
603 if (op->vertexData->vertexCount == 0)
607 op->vertexData->vertexStart = 0;
625 if (getParentSceneNode())
627 getParentSceneNode()->needUpdate();
636 Ogre::RenderOperation* op = rend->getRenderOperation();
637 if (op->vertexData->vertexCount == 0)
650 V_PointCloudRenderable::iterator it =
renderables_.begin();
651 V_PointCloudRenderable::iterator end =
renderables_.end();
652 for (; it != end; ++it)
654 queue->addRenderable((*it).get());
660 MovableObject::_notifyAttached(parent, isTagPoint);
708 V_PointCloudRenderable::iterator it =
renderables_.begin();
709 V_PointCloudRenderable::iterator end =
renderables_.end();
710 for (; it != end; ++it)
714 getUserObjectBindings().setUserAny(
"pick_handle", Ogre::Any(
colorToHandle(color)));
723 Ogre::Vector4 alpha(
alpha_, 0.0
f, 0.0
f, 0.0
f);
724 Ogre::Vector4 highlight(0.0
f, 0.0
f, 0.0
f, 0.0
f);
732 if (getParentSceneNode())
734 getParentSceneNode()->attachObject(rend.get());
754 mRenderOp.operationType = Ogre::RenderOperation::OT_POINT_LIST;
755 mRenderOp.useIndexes =
false;
756 mRenderOp.vertexData =
new Ogre::VertexData;
757 mRenderOp.vertexData->vertexStart = 0;
758 mRenderOp.vertexData->vertexCount = 0;
760 Ogre::VertexDeclaration* decl = mRenderOp.vertexData->vertexDeclaration;
763 decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_POSITION);
764 offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
768 decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_TEXTURE_COORDINATES, 0);
769 offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
772 decl->addElement(0, offset, Ogre::VET_COLOUR, Ogre::VES_DIFFUSE);
774 Ogre::HardwareVertexBufferSharedPtr vbuf =
775 Ogre::HardwareBufferManager::getSingleton().createVertexBuffer(
776 mRenderOp.vertexData->vertexDeclaration->getVertexSize(0), num_points,
777 Ogre::HardwareBuffer::HBU_DYNAMIC);
780 mRenderOp.vertexData->vertexBufferBinding->setBinding(0, vbuf);
785 delete mRenderOp.vertexData;
786 delete mRenderOp.indexData;
791 return mRenderOp.vertexData->vertexBufferBinding->getBuffer(0);
796 return Ogre::Math::Sqrt(std::max(mBox.getMaximum().squaredLength(), mBox.getMinimum().squaredLength()));
801 Ogre::Vector3 vMin, vMax, vMid, vDist;
802 vMin = mBox.getMinimum();
803 vMax = mBox.getMaximum();
804 vMid = ((vMax - vMin) * 0.5) + vMin;
805 vDist = cam->getDerivedPosition() - vMid;
807 return vDist.squaredLength();