shapes.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /*  Author: Ioan Sucan */
00036 
00037 #ifndef GEOMETRIC_SHAPES_SHAPES_
00038 #define GEOMETRIC_SHAPES_SHAPES_
00039 
00040 #include <cstdlib>
00041 #include <vector>
00042 #include <iostream>
00043 #include <boost/shared_ptr.hpp>
00044 #include <string>
00045 
00046 namespace octomap
00047 {
00048 class OcTree;
00049 }
00050 
00054 namespace shapes
00055 {
00056 
00058 enum ShapeType { UNKNOWN_SHAPE, SPHERE, CYLINDER, CONE, BOX, PLANE, MESH, OCTREE };
00059 
00060 
00062 class Shape
00063 {
00064 public:
00065   Shape();
00066   virtual ~Shape();
00067 
00069   virtual Shape* clone() const = 0;
00070 
00072   virtual void print(std::ostream &out = std::cout) const;
00073 
00075   void scale(double scale);
00076 
00078   void padd(double padding);
00079 
00081   virtual void scaleAndPadd(double scale, double padd) = 0;
00082 
00084   virtual bool isFixed() const;
00085 
00087   ShapeType type;
00088 };
00089 
00091 class Sphere : public Shape
00092 {
00093 public:
00094   Sphere();
00095 
00097   Sphere(double r);
00098 
00100   static const std::string STRING_NAME;
00101 
00102   virtual void scaleAndPadd(double scale, double padd);
00103   virtual Shape* clone() const;
00104   virtual void print(std::ostream &out = std::cout) const;
00105 
00107   double radius;
00108 };
00109 
00112 class Cylinder : public Shape
00113 {
00114 public:
00115   Cylinder();
00116 
00118   Cylinder(double r, double l);
00119 
00121   static const std::string STRING_NAME;
00122 
00123   virtual void scaleAndPadd(double scale, double padd);
00124   virtual Shape* clone() const;
00125   virtual void print(std::ostream &out = std::cout) const;
00126 
00128   double length;
00129 
00131   double radius;
00132 };
00133 
00137 class Cone : public Shape
00138 {
00139 public:
00140   Cone();
00141   Cone(double r, double l);
00142 
00144   static const std::string STRING_NAME;
00145 
00146   virtual void scaleAndPadd(double scale, double padd);
00147   virtual Shape* clone() const;
00148   virtual void print(std::ostream &out = std::cout) const;
00149 
00151   double length;
00152 
00154   double radius;
00155 };
00156 
00159 class Box : public Shape
00160 {
00161 public:
00162   Box();
00163   Box(double x, double y, double z);
00164 
00166   static const std::string STRING_NAME;
00167 
00168   virtual void scaleAndPadd(double scale, double padd);
00169   virtual Shape* clone() const;
00170   virtual void print(std::ostream &out = std::cout) const;
00171 
00173   double size[3];
00174 };
00175 
00181 class Mesh : public Shape
00182 {
00183 public:
00184 
00185   Mesh();
00186   Mesh(unsigned int v_count, unsigned int t_count);
00187   virtual ~Mesh();
00188 
00190   static const std::string STRING_NAME;
00191 
00192   virtual void scaleAndPadd(double scale, double padd);
00193   virtual Shape* clone() const;
00194   virtual void print(std::ostream &out = std::cout) const;
00195 
00197   void computeTriangleNormals();
00198 
00200   void computeVertexNormals();
00201 
00203   void mergeVertices(double threshold);
00204 
00206   unsigned int  vertex_count;
00207 
00210   double       *vertices;
00211 
00213   unsigned int  triangle_count;
00214 
00217   unsigned int *triangles;
00218 
00221   double       *triangle_normals;
00222 
00225   double       *vertex_normals;
00226 };
00227 
00229 class Plane : public Shape
00230 {
00231 public:
00232 
00233   Plane();
00234   Plane(double pa, double pb, double pc, double pd);
00235 
00237   static const std::string STRING_NAME;
00238 
00239   virtual Shape* clone() const;
00240   virtual void print(std::ostream &out = std::cout) const;
00241   virtual void scaleAndPadd(double scale, double padd);
00242   virtual bool isFixed() const;
00243 
00245   double a, b, c, d;
00246 };
00247 
00249 class OcTree : public Shape
00250 {
00251 public:
00252   OcTree();
00253   OcTree(const boost::shared_ptr<const octomap::OcTree> &t);
00254 
00256   static const std::string STRING_NAME;
00257 
00258   virtual Shape* clone() const;
00259   virtual void print(std::ostream &out = std::cout) const;
00260   virtual void scaleAndPadd(double scale, double padd);
00261   virtual bool isFixed() const;
00262 
00263   boost::shared_ptr<const octomap::OcTree> octree;
00264 };
00265 
00266 
00268 typedef boost::shared_ptr<Shape> ShapePtr;
00269 
00271 typedef boost::shared_ptr<const Shape> ShapeConstPtr;
00272 
00273 }
00274 
00275 #endif


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Thu Jun 8 2017 02:52:45