base_teb_edges.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Notes:
37  * The following class is derived from a class defined by the
38  * g2o-framework. g2o is licensed under the terms of the BSD License.
39  * Refer to the base class source for detailed licensing information.
40  *
41  * Author: Christoph Rösmann
42  *********************************************************************/
43 
44 #ifndef _BASE_TEB_EDGES_H_
45 #define _BASE_TEB_EDGES_H_
46 
48 
49 #include <g2o/core/base_binary_edge.h>
50 #include <g2o/core/base_unary_edge.h>
51 #include <g2o/core/base_multi_edge.h>
52 
53 namespace teb_local_planner
54 {
55 
56 
67 template <int D, typename E, typename VertexXi>
68 class BaseTebUnaryEdge : public g2o::BaseUnaryEdge<D, E, VertexXi>
69 {
70 public:
71 
72  using typename g2o::BaseUnaryEdge<D, E, VertexXi>::ErrorVector;
73  using g2o::BaseUnaryEdge<D, E, VertexXi>::computeError;
74 
81  ErrorVector& getError()
82  {
83  computeError();
84  return _error;
85  }
86 
90  virtual bool read(std::istream& is)
91  {
92  // TODO generic read
93  return true;
94  }
95 
99  virtual bool write(std::ostream& os) const
100  {
101  // TODO generic write
102  return os.good();
103  }
104 
109  void setTebConfig(const TebConfig& cfg)
110  {
111  cfg_ = &cfg;
112  }
113 
114 protected:
115 
116  using g2o::BaseUnaryEdge<D, E, VertexXi>::_error;
117  using g2o::BaseUnaryEdge<D, E, VertexXi>::_vertices;
118 
119  const TebConfig* cfg_;
120 
121 public:
122  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
123 };
124 
135 template <int D, typename E, typename VertexXi, typename VertexXj>
136 class BaseTebBinaryEdge : public g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>
137 {
138 public:
139 
140  using typename g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::ErrorVector;
141  using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::computeError;
142 
149  ErrorVector& getError()
150  {
151  computeError();
152  return _error;
153  }
154 
158  virtual bool read(std::istream& is)
159  {
160  // TODO generic read
161  return true;
162  }
163 
167  virtual bool write(std::ostream& os) const
168  {
169  // TODO generic write
170  return os.good();
171  }
172 
177  void setTebConfig(const TebConfig& cfg)
178  {
179  cfg_ = &cfg;
180  }
181 
182 protected:
183 
184  using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::_error;
185  using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::_vertices;
186 
187  const TebConfig* cfg_;
188 
189 public:
190  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
191 };
192 
193 
204 template <int D, typename E>
205 class BaseTebMultiEdge : public g2o::BaseMultiEdge<D, E>
206 {
207 public:
208 
209  using typename g2o::BaseMultiEdge<D, E>::ErrorVector;
210  using g2o::BaseMultiEdge<D, E>::computeError;
211 
212  // Overwrites resize() from the parent class
213  virtual void resize(size_t size)
214  {
215  g2o::BaseMultiEdge<D, E>::resize(size);
216 
217  for(std::size_t i=0; i<_vertices.size(); ++i)
218  _vertices[i] = NULL;
219  }
220 
227  ErrorVector& getError()
228  {
229  computeError();
230  return _error;
231  }
232 
236  virtual bool read(std::istream& is)
237  {
238  // TODO generic read
239  return true;
240  }
241 
245  virtual bool write(std::ostream& os) const
246  {
247  // TODO generic write
248  return os.good();
249  }
250 
255  void setTebConfig(const TebConfig& cfg)
256  {
257  cfg_ = &cfg;
258  }
259 
260 protected:
261 
262  using g2o::BaseMultiEdge<D, E>::_error;
263  using g2o::BaseMultiEdge<D, E>::_vertices;
264 
265  const TebConfig* cfg_;
266 
267 public:
268  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
269 };
270 
271 
272 
273 
274 
275 
276 } // end namespace
277 
278 #endif
virtual void resize(size_t size)
virtual bool write(std::ostream &os) const
Write values to an output stream.
virtual bool write(std::ostream &os) const
Write values to an output stream.
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
ErrorVector & getError()
Compute and return error / cost value.
Config class for the teb_local_planner and its components.
Definition: teb_config.h:61
virtual bool read(std::istream &is)
Read values from input stream.
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
const TebConfig * cfg_
Store TebConfig class for parameters.
virtual bool read(std::istream &is)
Read values from input stream.
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
Base edge connecting multiple vertices in the TEB optimization problem.
ErrorVector & getError()
Compute and return error / cost value.
const TebConfig * cfg_
Store TebConfig class for parameters.
ErrorVector & getError()
Compute and return error / cost value.
Base edge connecting two vertices in the TEB optimization problem.
const TebConfig * cfg_
Store TebConfig class for parameters.
virtual bool read(std::istream &is)
Read values from input stream.
virtual bool write(std::ostream &os) const
Write values to an output stream.
Base edge connecting a single vertex in the TEB optimization problem.


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 1 2022 02:26:31