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 <OgreSimpleRenderable.h>
00034 #include <OgreMovableObject.h>
00035 #include <OgreString.h>
00036 #include <OgreAxisAlignedBox.h>
00037 #include <OgreVector3.h>
00038 #include <OgreMaterial.h>
00039 #include <OgreColourValue.h>
00040 #include <OgreRoot.h>
00041 #include <OgreHardwareBufferManager.h>
00042 #include <OgreSharedPtr.h>
00043 
00044 #include <stdint.h>
00045 
00046 #include <vector>
00047 
00048 #include <boost/shared_ptr.hpp>
00049 
00050 namespace Ogre
00051 {
00052 class SceneManager;
00053 class ManualObject;
00054 class SceneNode;
00055 class RenderQueue;
00056 class Camera;
00057 class RenderSystem;
00058 class Matrix4;
00059 }
00060 
00061 namespace rviz
00062 {
00063 
00064 class PointCloud;
00065 class PointCloudRenderable : public Ogre::SimpleRenderable
00066 {
00067 public:
00068   PointCloudRenderable(PointCloud* parent, int num_points, bool use_tex_coords);
00069   ~PointCloudRenderable();
00070 
00071   Ogre::RenderOperation* getRenderOperation() { return &mRenderOp; }
00072   Ogre::HardwareVertexBufferSharedPtr getBuffer();
00073 
00074   virtual Ogre::Real getBoundingRadius(void) const;
00075   virtual Ogre::Real getSquaredViewDepth(const Ogre::Camera* cam) const;
00076   virtual void _notifyCurrentCamera(Ogre::Camera* camera);
00077   virtual unsigned short getNumWorldTransforms() const { return 1; }
00078   virtual void getWorldTransforms(Ogre::Matrix4* xform) const;
00079   virtual const Ogre::LightList& getLights() const;
00080 
00081 private:
00082   Ogre::MaterialPtr material_;
00083   PointCloud* parent_;
00084 };
00085 typedef boost::shared_ptr<PointCloudRenderable> PointCloudRenderablePtr;
00086 typedef std::vector<PointCloudRenderablePtr> V_PointCloudRenderable;
00087 
00098 class PointCloud : public Ogre::MovableObject
00099 {
00100 public:
00101   enum RenderMode
00102   {
00103     RM_POINTS,
00104     RM_SQUARES,
00105     RM_FLAT_SQUARES,
00106     RM_SPHERES,
00107     RM_TILES,
00108     RM_BOXES,
00109   };
00110 
00111   PointCloud();
00112   ~PointCloud();
00113 
00117   void clear();
00118 
00123   struct Point
00124   {
00125     inline void setColor(float r, float g, float b, float a=1.0)
00126     {
00127       color=Ogre::ColourValue(r, g, b, a);
00128     }
00129 
00130     Ogre::Vector3 position;
00131     Ogre::ColourValue color;
00132   };
00133 
00140   void addPoints( Point* points, uint32_t num_points );
00141 
00146   void popPoints( uint32_t num_points );
00147 
00151   void setRenderMode(RenderMode mode);
00158   void setDimensions( float width, float height, float depth );
00159 
00160   /*
00161    * If set to true, the size of each point will be multiplied by it z component.
00162    * (Used for depth image based point clouds)
00163    */
00164   void setAutoSize(bool auto_size);
00165 
00167   void setCommonDirection( const Ogre::Vector3& vec );
00169   void setCommonUpVector( const Ogre::Vector3& vec );
00170 
00175   void setAlpha( float alpha, bool per_point_alpha = false );
00176 
00177   void setPickColor(const Ogre::ColourValue& color);
00178   void setColorByIndex(bool set);
00179 
00180   void setHighlightColor( float r, float g, float b );
00181 
00182   virtual const Ogre::String& getMovableType() const { return sm_Type; }
00183   virtual const Ogre::AxisAlignedBox& getBoundingBox() const;
00184   virtual float getBoundingRadius() const;
00185   virtual void getWorldTransforms( Ogre::Matrix4* xform ) const;
00186   virtual unsigned short getNumWorldTransforms() const { return 1; }
00187   virtual void _updateRenderQueue( Ogre::RenderQueue* queue );
00188   virtual void _notifyCurrentCamera( Ogre::Camera* camera );
00189   virtual void _notifyAttached(Ogre::Node *parent, bool isTagPoint=false);
00190 #if (OGRE_VERSION_MAJOR >= 1 && OGRE_VERSION_MINOR >= 6)
00191   virtual void visitRenderables(Ogre::Renderable::Visitor* visitor, bool debugRenderables);
00192 #endif
00193 
00194   virtual void setName ( const std::string& name ) { mName = name; }
00195 
00196 private:
00197 
00198   uint32_t getVerticesPerPoint();
00199   PointCloudRenderablePtr createRenderable( int num_points );
00200   void regenerateAll();
00201   void shrinkRenderables();
00202 
00203   Ogre::AxisAlignedBox bounding_box_;       
00204   float bounding_radius_;                   
00205 
00206   typedef std::vector<Point> V_Point;
00207   V_Point points_;                          
00208   uint32_t point_count_;                    
00209 
00210   RenderMode render_mode_;
00211   float width_;                             
00212   float height_;                            
00213   float depth_;                             
00214   Ogre::Vector3 common_direction_;          
00215   Ogre::Vector3 common_up_vector_;          
00216 
00217   Ogre::MaterialPtr point_material_;
00218   Ogre::MaterialPtr square_material_;
00219   Ogre::MaterialPtr flat_square_material_;
00220   Ogre::MaterialPtr sphere_material_;
00221   Ogre::MaterialPtr tile_material_;
00222   Ogre::MaterialPtr box_material_;
00223   Ogre::MaterialPtr current_material_;
00224   float alpha_;
00225 
00226   bool color_by_index_;
00227 
00228   V_PointCloudRenderable renderables_;
00229 
00230   bool current_mode_supports_geometry_shader_;
00231   Ogre::ColourValue pick_color_;
00232 
00233   static Ogre::String sm_Type;              
00234 };
00235 
00236 } // namespace rviz
00237 
00238 #endif


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Tue Oct 3 2017 03:19:31