point_cloud.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef OGRE_TOOLS_OGRE_POINT_CLOUD_H
00031 #define OGRE_TOOLS_OGRE_POINT_CLOUD_H
00032 
00033 #include <OGRE/OgreSimpleRenderable.h>
00034 #include <OGRE/OgreMovableObject.h>
00035 #include <OGRE/OgreString.h>
00036 #include <OGRE/OgreAxisAlignedBox.h>
00037 #include <OGRE/OgreVector3.h>
00038 #include <OGRE/OgreMaterial.h>
00039 #include <OGRE/OgreColourValue.h>
00040 #include <OGRE/OgreRoot.h>
00041 #include <OGRE/OgreHardwareBufferManager.h>
00042 
00043 #include <stdint.h>
00044 
00045 #include <vector>
00046 
00047 #include <boost/shared_ptr.hpp>
00048 
00049 namespace Ogre
00050 {
00051 class SceneManager;
00052 class ManualObject;
00053 class SceneNode;
00054 class RenderQueue;
00055 class Camera;
00056 class RenderSystem;
00057 class Matrix4;
00058 }
00059 
00060 namespace rviz
00061 {
00062 
00063 class PointCloud;
00064 class PointCloudRenderable : public Ogre::SimpleRenderable
00065 {
00066 public:
00067   PointCloudRenderable(PointCloud* parent, int num_points, bool use_tex_coords);
00068   ~PointCloudRenderable();
00069 
00070   Ogre::RenderOperation* getRenderOperation() { return &mRenderOp; }
00071   Ogre::HardwareVertexBufferSharedPtr getBuffer();
00072 
00073   virtual Ogre::Real getBoundingRadius(void) const;
00074   virtual Ogre::Real getSquaredViewDepth(const Ogre::Camera* cam) const;
00075   virtual void _notifyCurrentCamera(Ogre::Camera* camera);
00076   virtual unsigned short getNumWorldTransforms() const { return 1; }
00077   virtual void getWorldTransforms(Ogre::Matrix4* xform) const;
00078   virtual const Ogre::LightList& getLights() const;
00079 
00080 private:
00081   Ogre::MaterialPtr material_;
00082   PointCloud* parent_;
00083 };
00084 typedef boost::shared_ptr<PointCloudRenderable> PointCloudRenderablePtr;
00085 typedef std::vector<PointCloudRenderablePtr> V_PointCloudRenderable;
00086 
00097 class PointCloud : public Ogre::MovableObject
00098 {
00099 public:
00100   enum RenderMode
00101   {
00102     RM_POINTS,
00103     RM_SQUARES,
00104     RM_FLAT_SQUARES,
00105     RM_SPHERES,
00106     RM_TILES,
00107     RM_BOXES,
00108   };
00109 
00110   PointCloud();
00111   ~PointCloud();
00112 
00116   void clear();
00117 
00122   struct Point
00123   {
00124     inline void setColor(float r, float g, float b, float a=1.0)
00125     {
00126       color=Ogre::ColourValue(r, g, b, a);
00127     }
00128 
00129     Ogre::Vector3 position;
00130     Ogre::ColourValue color;
00131   };
00132 
00139   void addPoints( Point* points, uint32_t num_points );
00140 
00145   void popPoints( uint32_t num_points );
00146 
00150   void setRenderMode(RenderMode mode);
00157   void setDimensions( float width, float height, float depth );
00158 
00159   /*
00160    * If set to true, the size of each point will be multiplied by it z component.
00161    * (Used for depth image based point clouds)
00162    */
00163   void setAutoSize(bool auto_size);
00164 
00166   void setCommonDirection( const Ogre::Vector3& vec );
00168   void setCommonUpVector( const Ogre::Vector3& vec );
00169 
00174   void setAlpha( float alpha, bool per_point_alpha = false );
00175 
00176   void setPickColor(const Ogre::ColourValue& color);
00177   void setColorByIndex(bool set);
00178 
00179   void setHighlightColor( float r, float g, float b );
00180 
00181   virtual const Ogre::String& getMovableType() const { return sm_Type; }
00182   virtual const Ogre::AxisAlignedBox& getBoundingBox() const;
00183   virtual float getBoundingRadius() const;
00184   virtual void getWorldTransforms( Ogre::Matrix4* xform ) const;
00185   virtual unsigned short getNumWorldTransforms() const { return 1; }
00186   virtual void _updateRenderQueue( Ogre::RenderQueue* queue );
00187   virtual void _notifyCurrentCamera( Ogre::Camera* camera );
00188   virtual void _notifyAttached(Ogre::Node *parent, bool isTagPoint=false);
00189 #if (OGRE_VERSION_MAJOR >= 1 && OGRE_VERSION_MINOR >= 6)
00190   virtual void visitRenderables(Ogre::Renderable::Visitor* visitor, bool debugRenderables);
00191 #endif
00192 
00193   virtual void setName ( const std::string& name ) { mName = name; }
00194 
00195 private:
00196 
00197   uint32_t getVerticesPerPoint();
00198   PointCloudRenderablePtr createRenderable( int num_points );
00199   void regenerateAll();
00200   void shrinkRenderables();
00201 
00202   Ogre::AxisAlignedBox bounding_box_;       
00203   float bounding_radius_;                   
00204 
00205   typedef std::vector<Point> V_Point;
00206   V_Point points_;                          
00207   uint32_t point_count_;                    
00208 
00209   RenderMode render_mode_;
00210   float width_;                             
00211   float height_;                            
00212   float depth_;                             
00213   Ogre::Vector3 common_direction_;          
00214   Ogre::Vector3 common_up_vector_;          
00215 
00216   Ogre::ResourcePtr point_material_;
00217   Ogre::ResourcePtr square_material_;
00218   Ogre::ResourcePtr flat_square_material_;
00219   Ogre::ResourcePtr sphere_material_;
00220   Ogre::ResourcePtr tile_material_;
00221   Ogre::ResourcePtr box_material_;
00222   Ogre::MaterialPtr current_material_;
00223   float alpha_;
00224 
00225   bool color_by_index_;
00226 
00227   V_PointCloudRenderable renderables_;
00228 
00229   bool current_mode_supports_geometry_shader_;
00230   Ogre::ColourValue pick_color_;
00231 
00232   static Ogre::String sm_Type;              
00233 };
00234 
00235 } // namespace rviz
00236 
00237 #endif


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:35