base_teb_edges.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016,
00006  *  TU Dortmund - Institute of Control Theory and Systems Engineering.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the institute nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  * 
00036  * Notes:
00037  * The following class is derived from a class defined by the
00038  * g2o-framework. g2o is licensed under the terms of the BSD License.
00039  * Refer to the base class source for detailed licensing information.
00040  *
00041  * Author: Christoph Rösmann
00042  *********************************************************************/
00043 
00044 #ifndef _BASE_TEB_EDGES_H_
00045 #define _BASE_TEB_EDGES_H_
00046 
00047 #include <teb_local_planner/teb_config.h>
00048 
00049 #include <g2o/core/base_binary_edge.h>
00050 #include <g2o/core/base_unary_edge.h>
00051 #include <g2o/core/base_multi_edge.h>
00052 
00053 #include <cmath>
00054 
00055 namespace teb_local_planner
00056 {
00057     
00058     
00069 template <int D, typename E, typename VertexXi>
00070 class BaseTebUnaryEdge : public g2o::BaseUnaryEdge<D, E, VertexXi>
00071 {
00072 public:
00073             
00074   using typename g2o::BaseUnaryEdge<D, E, VertexXi>::ErrorVector;
00075   using g2o::BaseUnaryEdge<D, E, VertexXi>::computeError;
00076     
00080   BaseTebUnaryEdge()
00081   {
00082       _vertices[0] = NULL;
00083   }
00084   
00091   virtual ~BaseTebUnaryEdge()
00092   {
00093       if(_vertices[0])
00094         _vertices[0]->edges().erase(this);
00095   }
00096 
00103   ErrorVector& getError()
00104   {
00105     computeError();
00106     return _error;
00107   }
00108   
00112   virtual bool read(std::istream& is)
00113   {
00114     // TODO generic read
00115     return true;
00116   }
00117 
00121   virtual bool write(std::ostream& os) const
00122   {
00123     // TODO generic write
00124     return os.good();
00125   }
00126 
00131   void setTebConfig(const TebConfig& cfg)
00132   {
00133     cfg_ = &cfg;
00134   }
00135     
00136 protected:
00137     
00138   using g2o::BaseUnaryEdge<D, E, VertexXi>::_error;
00139   using g2o::BaseUnaryEdge<D, E, VertexXi>::_vertices;
00140   
00141   const TebConfig* cfg_; 
00142   
00143 public:
00144   EIGEN_MAKE_ALIGNED_OPERATOR_NEW   
00145 };
00146 
00157 template <int D, typename E, typename VertexXi, typename VertexXj>
00158 class BaseTebBinaryEdge : public g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>
00159 {
00160 public:
00161     
00162   using typename g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::ErrorVector;
00163   using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::computeError;
00164   
00168   BaseTebBinaryEdge()
00169   {
00170       _vertices[0] = _vertices[1] = NULL;
00171   }
00172   
00179   virtual ~BaseTebBinaryEdge()
00180   {
00181     if(_vertices[0])
00182         _vertices[0]->edges().erase(this);
00183     if(_vertices[1])
00184         _vertices[1]->edges().erase(this);
00185   }
00186 
00193   ErrorVector& getError()
00194   {
00195     computeError();
00196     return _error;
00197   }
00198   
00202   virtual bool read(std::istream& is)
00203   {
00204     // TODO generic read
00205     return true;
00206   }
00207 
00211   virtual bool write(std::ostream& os) const
00212   {
00213     // TODO generic write
00214     return os.good();
00215   }
00216 
00221   void setTebConfig(const TebConfig& cfg)
00222   {
00223     cfg_ = &cfg;
00224   }
00225   
00226 protected:
00227   
00228   using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::_error;
00229   using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::_vertices;
00230     
00231   const TebConfig* cfg_; 
00232   
00233 public:
00234   EIGEN_MAKE_ALIGNED_OPERATOR_NEW   
00235 };
00236 
00237 
00248 template <int D, typename E>
00249 class BaseTebMultiEdge : public g2o::BaseMultiEdge<D, E>
00250 {
00251 public:
00252   
00253   using typename g2o::BaseMultiEdge<D, E>::ErrorVector;
00254   using g2o::BaseMultiEdge<D, E>::computeError;
00255     
00259   BaseTebMultiEdge()
00260   {
00261 //     for(std::size_t i=0; i<_vertices.size(); ++i)
00262 //         _vertices[i] = NULL;
00263   }
00264   
00271   virtual ~BaseTebMultiEdge()
00272   {
00273     for(std::size_t i=0; i<_vertices.size(); ++i)
00274     {
00275         if(_vertices[i])
00276             _vertices[i]->edges().erase(this);
00277     }
00278   }
00279   
00280   // Overwrites resize() from the parent class
00281   virtual void resize(size_t size)
00282   {
00283       g2o::BaseMultiEdge<D, E>::resize(size);
00284       
00285       for(std::size_t i=0; i<_vertices.size(); ++i)
00286         _vertices[i] = NULL;
00287   }
00288 
00295   ErrorVector& getError()
00296   {
00297     computeError();
00298     return _error;
00299   }
00300   
00304   virtual bool read(std::istream& is)
00305   {
00306     // TODO generic read
00307     return true;
00308   }
00309 
00313   virtual bool write(std::ostream& os) const
00314   {
00315     // TODO generic write
00316     return os.good();
00317   }
00318 
00323   void setTebConfig(const TebConfig& cfg)
00324   {
00325     cfg_ = &cfg;
00326   }
00327   
00328 protected:
00329     
00330   using g2o::BaseMultiEdge<D, E>::_error;
00331   using g2o::BaseMultiEdge<D, E>::_vertices;
00332   
00333   const TebConfig* cfg_; 
00334   
00335 public:
00336   EIGEN_MAKE_ALIGNED_OPERATOR_NEW   
00337 };
00338 
00339 
00340 
00341 
00342 
00343 
00344 } // end namespace
00345 
00346 #endif


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sat Jun 8 2019 20:21:34