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> 52 #define VERTEX_BUFFER_CAPACITY (36 * 1024 * 10) 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,
64 0.0f, 1.0f, 0.0f, -0.866025404f, -0.5f, 0.0f, 0.866025404f, -0.5f, 0.0f,
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,
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,
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);
168 *xform = _getParentNodeFullTransform();
177 if (getParentSceneNode())
179 V_PointCloudRenderable::iterator it =
renderables_.begin();
180 V_PointCloudRenderable::iterator end =
renderables_.end();
181 for (; it != end; ++it)
183 getParentSceneNode()->detachObject(it->get());
185 getParentSceneNode()->needUpdate();
215 Ogre::Vector4 highlight(r, g, b, 0.0
f);
217 V_PointCloudRenderable::iterator it =
renderables_.begin();
218 V_PointCloudRenderable::iterator end =
renderables_.end();
219 for (; it != end; ++it)
259 bool geom_support_changed =
false;
267 geom_support_changed =
true;
278 geom_support_changed =
true;
286 geom_support_changed =
true;
292 if (geom_support_changed)
297 V_PointCloudRenderable::iterator it =
renderables_.begin();
298 V_PointCloudRenderable::iterator end =
renderables_.end();
299 for (; it != end; ++it)
315 V_PointCloudRenderable::iterator it =
renderables_.begin();
316 V_PointCloudRenderable::iterator end =
renderables_.end();
317 for (; it != end; ++it)
325 V_PointCloudRenderable::iterator it =
renderables_.begin();
326 V_PointCloudRenderable::iterator end =
renderables_.end();
327 for (; it != end; ++it)
337 V_PointCloudRenderable::iterator it =
renderables_.begin();
338 V_PointCloudRenderable::iterator end =
renderables_.end();
339 for (; it != end; ++it)
349 V_PointCloudRenderable::iterator it =
renderables_.begin();
350 V_PointCloudRenderable::iterator end =
renderables_.end();
351 for (; it != end; ++it)
353 (*it)->setCustomParameter(
UP_PARAMETER, Ogre::Vector4(vec));
359 if (mat->getBestTechnique())
361 mat->getBestTechnique()->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
362 mat->getBestTechnique()->setDepthWriteEnabled(
false);
368 if (mat->getBestTechnique())
370 mat->getBestTechnique()->setSceneBlending(Ogre::SBT_REPLACE);
371 mat->getBestTechnique()->setDepthWriteEnabled(
true);
379 if (alpha < 0.9998 || per_point_alpha)
399 V_PointCloudRenderable::iterator it =
renderables_.begin();
400 V_PointCloudRenderable::iterator end =
renderables_.end();
401 for (; it != end; ++it)
413 Ogre::Root*
root = Ogre::Root::getSingletonPtr();
421 memcpy(begin, points,
sizeof(
Point) * num_points);
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;
475 Ogre::HardwareVertexBufferSharedPtr vbuf;
476 void* vdata =
nullptr;
477 Ogre::RenderOperation* op =
nullptr;
478 float* fptr =
nullptr;
480 Ogre::AxisAlignedBox aabb;
482 uint32_t current_vertex_count = 0;
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)
491 while (!rend || current_vertex_count >= buffer_size)
495 ROS_ASSERT(current_vertex_count == buffer_size);
497 op->vertexData->vertexCount = rend->getBuffer()->getNumVertices() - op->vertexData->vertexStart;
498 ROS_ASSERT(op->vertexData->vertexCount + op->vertexData->vertexStart <=
499 rend->getBuffer()->getNumVertices());
501 rend->setBoundingBox(aabb);
508 vbuf = rend->getBuffer();
509 vdata = vbuf->lock(Ogre::HardwareBuffer::HBL_NO_OVERWRITE);
511 op = rend->getRenderOperation();
512 op->operationType = op_type;
513 current_vertex_count = 0;
515 vertex_size = op->vertexData->vertexDeclaration->getVertexSize(0);
516 fptr = (
float*)((uint8_t*)vdata);
521 const Point& p = points[current_point];
531 c.r = ((color >> 16) & 0xff) / 255.0f;
532 c.g = ((color >> 8) & 0xff) / 255.0f;
533 c.b = (color & 0xff) / 255.0
f;
534 root->convertColourValue(c, &color);
538 root->convertColourValue(p.
color, &color);
548 for (uint32_t j = 0; j < vpp; ++j, ++current_vertex_count)
556 *fptr++ = vertices[(j * 3)];
557 *fptr++ = vertices[(j * 3) + 1];
558 *fptr++ = vertices[(j * 3) + 2];
561 uint32_t* iptr = (uint32_t*)fptr;
565 ROS_ASSERT((uint8_t*)fptr <= (uint8_t*)vdata + rend->getBuffer()->getNumVertices() * vertex_size);
566 Q_UNUSED(vertex_size);
570 op->vertexData->vertexCount = current_vertex_count - op->vertexData->vertexStart;
571 rend->setBoundingBox(aabb);
573 ROS_ASSERT(op->vertexData->vertexCount + op->vertexData->vertexStart <=
574 rend->getBuffer()->getNumVertices());
582 if (getParentSceneNode())
584 getParentSceneNode()->needUpdate();
598 uint32_t popped_count = 0;
599 while (popped_count < num_points * vpp)
602 Ogre::RenderOperation* op = rend->getRenderOperation();
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;
608 popped_count += popped;
610 if (op->vertexData->vertexCount == 0)
614 op->vertexData->vertexStart = 0;
632 if (getParentSceneNode())
634 getParentSceneNode()->needUpdate();
643 Ogre::RenderOperation* op = rend->getRenderOperation();
644 if (op->vertexData->vertexCount == 0)
657 MovableObject::_notifyCurrentCamera(camera);
662 V_PointCloudRenderable::iterator it =
renderables_.begin();
663 V_PointCloudRenderable::iterator end =
renderables_.end();
664 for (; it != end; ++it)
666 queue->addRenderable((*it).get());
672 MovableObject::_notifyAttached(parent, isTagPoint);
720 V_PointCloudRenderable::iterator it =
renderables_.begin();
721 V_PointCloudRenderable::iterator end =
renderables_.end();
722 for (; it != end; ++it)
726 getUserObjectBindings().setUserAny(
"pick_handle", Ogre::Any(
colorToHandle(color)));
735 Ogre::Vector4 alpha(
alpha_, 0.0
f, 0.0
f, 0.0
f);
736 Ogre::Vector4 highlight(0.0
f, 0.0
f, 0.0
f, 0.0
f);
744 if (getParentSceneNode())
746 getParentSceneNode()->attachObject(rend.get());
753 #if (OGRE_VERSION_MAJOR >= 1 && OGRE_VERSION_MINOR >= 6) 754 void PointCloud::visitRenderables(Ogre::Renderable::Visitor* ,
bool )
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;
774 Ogre::VertexDeclaration* decl = mRenderOp.vertexData->vertexDeclaration;
777 decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_POSITION);
778 offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
782 decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_TEXTURE_COORDINATES, 0);
783 offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
786 decl->addElement(0, offset, Ogre::VET_COLOUR, Ogre::VES_DIFFUSE);
788 Ogre::HardwareVertexBufferSharedPtr vbuf =
789 Ogre::HardwareBufferManager::getSingleton().createVertexBuffer(
790 mRenderOp.vertexData->vertexDeclaration->getVertexSize(0), num_points,
791 Ogre::HardwareBuffer::HBU_DYNAMIC);
794 mRenderOp.vertexData->vertexBufferBinding->setBinding(0, vbuf);
799 delete mRenderOp.vertexData;
800 delete mRenderOp.indexData;
805 return mRenderOp.vertexData->vertexBufferBinding->getBuffer(0);
810 SimpleRenderable::_notifyCurrentCamera(camera);
815 return Ogre::Math::Sqrt(std::max(mBox.getMaximum().squaredLength(), mBox.getMinimum().squaredLength()));
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;
826 return vDist.squaredLength();
void addPoints(Point *points, uint32_t num_points)
Add points to this point cloud.
Ogre::MaterialPtr current_material_
Ogre::MaterialPtr sphere_material_
std::vector< Point > V_Point
void setAlphaBlending(const Ogre::MaterialPtr &mat)
Ogre::Real getBoundingRadius() const override
void setRenderMode(RenderMode mode)
Set what type of rendering primitives should be used, currently points, billboards and boxes are supp...
#define AUTO_SIZE_PARAMETER
uint32_t point_count_
The number of points currently in points_.
void setPickColor(const Ogre::ColourValue &color)
Ogre::HardwareVertexBufferSharedPtr getBuffer()
static float g_box_vertices[6 *6 *3]
void setColorByIndex(bool set)
const Ogre::LightList & getLights() const override
Ogre::AxisAlignedBox bounding_box_
The bounding box of this point cloud.
~PointCloudRenderable() override
Ogre::MaterialPtr flat_square_material_
void popPoints(uint32_t num_points)
Remove a number of points from this point cloud.
V_Point points_
The list of points we're displaying. Allocates to a high-water-mark.
virtual void getWorldTransforms(Ogre::Matrix4 *xform) const
Ogre::MaterialPtr square_material_
Ogre::Vector3 common_direction_
See Ogre::BillboardSet::setCommonDirection.
void _notifyCurrentCamera(Ogre::Camera *camera) override
#define VERTEX_BUFFER_CAPACITY
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_
Ogre::MaterialPtr tile_material_
#define HIGHLIGHT_PARAMETER
Representation of a point, with x/y/z position and r/g/b color.
void setDimensions(float width, float height, float depth)
Set the dimensions of the billboards used to render each point.
void setAlpha(float alpha, bool per_point_alpha=false)
void clear()
Clear all the points.
Ogre::MaterialPtr box_material_
void _notifyCurrentCamera(Ogre::Camera *camera) override
#define PICK_COLOR_PARAMETER
float bounding_radius_
The bounding radius of this point cloud.
void setReplace(const Ogre::MaterialPtr &mat)
static void removeMaterial(Ogre::MaterialPtr &material)
uint32_t colorToHandle(Ogre::PixelFormat fmt, uint32_t col)
static float g_billboard_vertices[6 *3]
const Ogre::AxisAlignedBox & getBoundingBox() const override
Ogre::ColourValue pick_color_
uint32_t getVerticesPerPoint()
void setHighlightColor(float r, float g, float b)
A visual representation of a set of points.
V_PointCloudRenderable renderables_
PointCloudRenderable(PointCloud *parent, int num_points, bool use_tex_coords)
Ogre::MaterialPtr point_material_
void setCommonDirection(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonDirection.
Ogre::Vector3 common_up_vector_
See Ogre::BillboardSet::setCommonUpVector.
static float g_point_vertices[3]
void _notifyAttached(Ogre::Node *parent, bool isTagPoint=false) override
static float g_billboard_sphere_vertices[3 *3]
void _updateRenderQueue(Ogre::RenderQueue *queue) override
static Ogre::String sm_Type
The "renderable type" used by Ogre.
void setAutoSize(bool auto_size)
float getBoundingRadius() const override
PointCloudRenderablePtr createRenderable(int num_points)
void getWorldTransforms(Ogre::Matrix4 *xform) const override