renderable.h
Go to the documentation of this file.
00001 /* 
00002  * Copyright (c) 2011, Nico Blodow <blodow@cs.tum.edu>
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 Intelligent Autonomous Systems Group/
00014  *       Technische Universitaet Muenchen nor the names of its contributors 
00015  *       may be used to endorse or promote products derived from this software 
00016  *       without specific prior written permission.
00017  * 
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028  * POSSIBILITY OF SUCH DAMAGE.
00029  */
00030 
00031 #ifndef REALTIME_PERCEPTION_RENDERABLE_H_
00032 #define REALTIME_PERCEPTION_RENDERABLE_H_
00033 
00034 #include <GL3/gl3.h>
00035 #include <tf/tf.h>
00036 // this is necessary for diamondback. for more recent ROS versions, use:
00037 // #include <urdf_interface/color.h>
00038 #include <urdf_interface/color.h>
00039 
00040 #include <assimp/aiScene.h>
00041 
00042 // forward declare
00043 struct aiScene;
00044 struct aiMesh;
00045 
00046 namespace realtime_urdf_filter
00047 {
00048 
00049 struct Renderable
00050 { 
00051   void setLinkName (std::string n);
00052   virtual void render () = 0;
00053   std::string name;
00054 
00055 //  tf::Vector3 offset_t;
00056 //  tf::Quaternion offset_q;
00057 //  tf::Vector3 t;
00058 //  tf::Quaternion q;
00059 
00060   tf::Transform link_offset;
00061   tf::Transform link_to_fixed;
00062   tf::Transform fixed_to_target;
00063 
00064   urdf::Color color;
00065   void applyTransform ();
00066   void unapplyTransform ();
00067 };
00068 
00069 struct RenderableBox : public Renderable
00070 {
00071   RenderableBox (float dimx, float dimy, float dimz);
00072 
00073   virtual void render ();
00074 
00075   float dimx, dimy, dimz;
00076 protected: 
00077   void createBoxVBO ();
00078   GLuint vbo;
00079 };
00080 
00081 struct RenderableSphere : public Renderable
00082 {
00083   RenderableSphere (float radius);
00084 
00085   virtual void render ();
00086 
00087   float radius;
00088 };
00089 
00090 struct RenderableCylinder : public Renderable
00091 {
00092   RenderableCylinder (float radius, float length);
00093 
00094   virtual void render ();
00095 
00096   float radius;
00097   float length;
00098 };
00099 
00100 // meshes are a tad more complicated than boxes and spheres
00101 struct RenderableMesh : public Renderable
00102 {
00103   RenderableMesh (std::string meshname);
00104 
00105   virtual void render ();
00106   void setScale (float x, float y, float z);
00107 
00108 private:
00109   struct Vertex
00110   {
00111     float x,y,z;
00112     float nx,ny,nz;
00113     Vertex (float x, float y, float z, float nx, float ny, float nz)
00114       : x(x), y(y), z(z), nx(nx), ny(ny), nz(nz)
00115     {}
00116   };
00117 
00118   struct SubMesh
00119   {
00120     enum {INVALID_VALUE = 0xFFFFFFFF};
00121     SubMesh ();
00122     ~SubMesh ();
00123     void init (const std::vector<Vertex>& vertices,
00124                const std::vector<unsigned int>& indices);
00125     GLuint vbo, ibo;
00126     unsigned int num_indices;
00127   };
00128 
00129   void fromAssimpScene (const aiScene* scene);
00130   void initMesh (unsigned int i, const aiMesh* mesh, const aiNode* node);
00131 
00132   std::vector<SubMesh> meshes;
00133   double scale_x;
00134   double scale_y;
00135   double scale_z;
00136 
00137   std::string meshname_;
00138 };
00139 
00140 
00141 
00142 } // end namespace
00143 
00144 #endif
00145 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


realtime_urdf_filter
Author(s): Nico Blodow
autogenerated on Thu May 23 2013 16:50:36