nurbs_data.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012-, Open Perception, 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 copyright holder(s) 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  *
00036  */
00037 
00038 #ifndef NURBS_DATA_H
00039 #define NURBS_DATA_H
00040 
00041 #include <vector>
00042 #include <list>
00043 #include <stdio.h>
00044 
00045 #undef Success
00046 #include <Eigen/StdVector>
00047 
00048 namespace pcl
00049 {
00050   namespace on_nurbs
00051   {
00052 
00053     // http://eigen.tuxfamily.org/dox-devel/TopicStlContainers.html
00054     typedef std::vector<Eigen::Vector2i, Eigen::aligned_allocator<Eigen::Vector2i> > vector_vec2i;
00055     typedef std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > vector_vec2d;
00056     typedef std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > vector_vec3d;
00057 
00060     struct NurbsDataSurface
00061     {
00062       Eigen::Matrix3d eigenvectors;
00063       Eigen::Vector3d mean;
00064 
00065       vector_vec3d interior; 
00066       std::vector<double> interior_weight; 
00067       std::vector<double> interior_error; 
00068       vector_vec2d interior_param; 
00069       vector_vec3d interior_line_start; 
00070       vector_vec3d interior_line_end; 
00071       vector_vec3d interior_normals; 
00072 
00073       vector_vec3d boundary; 
00074       std::vector<double> boundary_weight; 
00075       std::vector<double> boundary_error; 
00076       vector_vec2d boundary_param; 
00077       vector_vec3d boundary_line_start; 
00078       vector_vec3d boundary_line_end; 
00079       vector_vec3d boundary_normals; 
00080 
00081       vector_vec3d common_boundary_point;
00082       std::vector<unsigned> common_boundary_idx;
00083       vector_vec2d common_boundary_param;
00084 
00085       std::vector<unsigned> common_idx;
00086       vector_vec2d common_param1;
00087       vector_vec2d common_param2;
00088 
00090       inline void
00091       clear_interior ()
00092       {
00093         interior.clear ();
00094         interior_weight.clear ();
00095         interior_error.clear ();
00096         interior_param.clear ();
00097         interior_line_start.clear ();
00098         interior_line_end.clear ();
00099         interior_normals.clear ();
00100       }
00101 
00103       inline void
00104       clear_boundary ()
00105       {
00106         boundary.clear ();
00107         boundary_weight.clear ();
00108         boundary_error.clear ();
00109         boundary_param.clear ();
00110         boundary_line_start.clear ();
00111         boundary_line_end.clear ();
00112         boundary_normals.clear ();
00113       }
00114 
00115       inline void
00116       clear_common()
00117       {
00118         common_idx.clear();
00119         common_param1.clear();
00120         common_param2.clear();
00121       }
00122 
00124       inline void
00125       clear_common_boundary ()
00126       {
00127         common_boundary_point.clear ();
00128         common_boundary_idx.clear ();
00129         common_boundary_param.clear ();
00130       }
00131 
00132       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00133     };
00134 
00137     struct NurbsDataCurve
00138     {
00139       Eigen::Matrix3d eigenvectors;
00140       Eigen::Vector3d mean;
00141 
00142       vector_vec3d interior; 
00143       std::vector<double> interior_error; 
00144       std::vector<double> interior_param; 
00145       vector_vec3d interior_line_start; 
00146       vector_vec3d interior_line_end; 
00147       vector_vec3d interior_normals; 
00148 
00150       inline void
00151       clear_interior ()
00152       {
00153         interior.clear ();
00154         interior_error.clear ();
00155         interior_param.clear ();
00156         interior_line_start.clear ();
00157         interior_line_end.clear ();
00158         interior_normals.clear ();
00159       }
00160 
00161       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00162     };
00163 
00166     struct NurbsDataCurve2d
00167     {
00168       Eigen::Matrix2d eigenvectors;
00169       Eigen::Vector2d mean;
00170 
00171       vector_vec2d interior; 
00172       std::vector<double> interior_error; 
00173       std::vector<double> interior_param; 
00174       vector_vec2d interior_line_start; 
00175       vector_vec2d interior_line_end; 
00176       vector_vec2d interior_normals; 
00177 
00178       std::vector<double> interior_weight;
00179       std::vector<bool> interior_weight_function;
00180 
00181       vector_vec2d closest_points;
00182       std::vector<double> closest_points_param;
00183       std::vector<double> closest_points_error;
00184 
00185       int interior_ncps_prev;
00186       int closest_ncps_prev;
00187 
00188       vector_vec2d interior_tangents;
00189       std::vector<double> interior_rho;
00190 
00191       vector_vec2d closest_tangents;
00192       vector_vec2d closest_normals;
00193       std::vector<double> closest_rho;
00194 
00196       inline void
00197       clear_interior ()
00198       {
00199         interior.clear ();
00200         interior_error.clear ();
00201         interior_param.clear ();
00202         interior_line_start.clear ();
00203         interior_line_end.clear ();
00204         interior_normals.clear ();
00205       }
00206 
00207       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00208     };
00209 
00210   }
00211 }
00212 
00213 #endif
00214 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:26:09