rtcMesh3D.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2007
00003  * Robert Bosch LLC
00004  * Research and Technology Center North America
00005  * Palo Alto, California
00006  *
00007  * All rights reserved.
00008  *
00009  *------------------------------------------------------------------------------
00010  * project ....: PUMA: Probablistic Unsupervised Model Acquisition
00011  * file .......: Mesh3D.h
00012  * authors ....: Benjamin Pitzer
00013  * organization: Robert Bosch LLC
00014  * creation ...: 02/29/2008
00015  * modified ...: $Date:2008-03-03 10:26:02 -0800 (Mon, 03 Mar 2008) $
00016  * changed by .: $Author:benjaminpitzer $
00017  * revision ...: $Revision:141 $
00018  */
00019 #ifndef MESH3D_H_
00020 #define MESH3D_H_
00021 
00022 //== INCLUDES ==================================================================
00023 #include <rtc/rtcBase.h>
00024 #include <rtc/rtcIOObject.h>
00025 #include <rtc/rtcPose3D.h>
00026 #include <rtc/rtcImage.h>
00027 #ifndef NO_GRAPHICS
00028 #include <rtc/rtcTexture.h>
00029 #endif
00030 #include "rtc/rtcVertex3D.h"
00031 #include "rtc/rtcFace3D.h"
00032 
00033 #include "sensor_msgs/CameraInfo.h"
00034 
00035 //== NAMESPACES ================================================================
00036 namespace rtc {
00037 
00038 #define MESH_FLAG_HAS_VERTEX_NORMAL  0x01
00039 #define MESH_FLAG_HAS_FACE_NORMAL    0x02
00040 #define MESH_FLAG_HAS_VERTEX_COLOR   0x04
00041 #define MESH_FLAG_HAS_FACE_COLOR     0x08
00042 #define MESH_FLAG_HAS_VERTEX_FLAG    0x10
00043 #define MESH_FLAG_HAS_FACE_FLAG      0x20
00044 #define MESH_FLAG_HAS_TEXTURE        0x40
00045 #define MESH_FLAG_HAS_TEXTUREMASK    0x80
00046 #define MESH_FLAG_HAS_IMAGE_POSE     0x81
00047 #define MESH_FLAG_HAS_CAMERA_INFO    0x82
00048 #define MESH_FLAG_HAS_FRAME_ID       0x83
00049 
00050 typedef std::vector<Vertex3D*> VecVertex3D;
00051 typedef std::vector<Face3D*> VecFace3D;
00052 
00053 //== CLASS DEFINITION ==========================================================
00054 class Mesh3D : public IOObject
00055 {
00056 public:
00057   // standard c'tor and d'tor
00058   Mesh3D();
00059   virtual ~Mesh3D();
00060   // copy c'tor
00061   Mesh3D(const Mesh3D& other);
00062   const Mesh3D &operator=(const Mesh3D& other);
00063 
00064   // performs updateValid, updateBoundary, and updateNormals
00065   void update();
00066   // calculates normals for valid and non-boundary points
00067   void updateNormals();
00068   // clear all edges and vertices
00069   void clear();
00070   void set(const Mesh3D& other);
00071 
00072   // face methods
00073   int numFaces() const;
00074   Face3D* addFace(Face3D* face);
00075   Face3D* addFace(int v0, int v1, int v2);
00076   Face3D* addFace(int vhandles[3]);
00077   // update edges
00078   void updateFaces();
00079 
00080   //gpu operation
00081   void loadTexture();
00082   void unloadTexture();
00083 
00084   // vertex methods
00085   int numVertices() const;
00086   Vertex3D* addVertex(Vertex3D* vertex);
00087   Vertex3D* addVertex(const Point3Df& p);
00088   // update all vertices
00089   void updateVertices();
00090 
00091   // flags
00092   void setFlag(int flag, bool value);
00093   bool getFlag(int flag) const;
00094   bool hasVertexNormals() const;
00095   bool hasFaceNormals() const;
00096   bool hasVertexColors() const;
00097   bool hasFaceColors() const;
00098   bool hasVertexFlags() const;
00099   bool hasFaceFlags() const;
00100   bool hasTexture() const;
00101   bool hasImagePose() const;
00102   bool hasCameraInfo() const;
00103   bool hasFrameID() const;
00104 
00105   // stream IO
00106   virtual bool write(OutputHandler &oh) const;
00107   virtual bool read(InputHandler &ih);
00108   void write(FILE *fp) const;
00109   void read(FILE *fp);
00110 
00111   Pose3Df pose;
00112   int flags;
00113   VecVertex3D vertices;
00114   VecFace3D faces;
00115 
00116   //texture mapping
00117 #ifndef NO_GRAPHICS
00118   Texture texture;
00119 #endif
00120   Image<Vec3uc> teximage;
00121   Array2i texmask;
00122   Pose3Df image_pose;
00123   sensor_msgs::CameraInfo camera_info;
00124   std::string frame_id;
00125 };
00126 
00127 
00128 //==============================================================================
00129 } // NAMESPACE rtc
00130 //==============================================================================
00131 #endif // MESH3D_H_ defined
00132 //==============================================================================


rtc
Author(s): Benjamin Pitzer
autogenerated on Mon Oct 6 2014 10:07:34