44 #ifndef _BASE_TEB_EDGES_H_ 45 #define _BASE_TEB_EDGES_H_ 49 #include <g2o/core/base_binary_edge.h> 50 #include <g2o/core/base_unary_edge.h> 51 #include <g2o/core/base_multi_edge.h> 69 template <
int D,
typename E,
typename VertexXi>
74 using typename g2o::BaseUnaryEdge<D, E, VertexXi>::ErrorVector;
75 using g2o::BaseUnaryEdge<D, E, VertexXi>::computeError;
94 _vertices[0]->edges().erase(
this);
112 virtual bool read(std::istream& is)
121 virtual bool write(std::ostream& os)
const 138 using g2o::BaseUnaryEdge<D, E, VertexXi>::_error;
139 using g2o::BaseUnaryEdge<D, E, VertexXi>::_vertices;
144 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
157 template <
int D,
typename E,
typename VertexXi,
typename VertexXj>
162 using typename g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::ErrorVector;
163 using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::computeError;
170 _vertices[0] = _vertices[1] = NULL;
182 _vertices[0]->edges().erase(
this);
184 _vertices[1]->edges().erase(
this);
202 virtual bool read(std::istream& is)
211 virtual bool write(std::ostream& os)
const 228 using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::_error;
229 using g2o::BaseBinaryEdge<D, E, VertexXi, VertexXj>::_vertices;
234 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
248 template <
int D,
typename E>
253 using typename g2o::BaseMultiEdge<D, E>::ErrorVector;
254 using g2o::BaseMultiEdge<D, E>::computeError;
273 for(std::size_t i=0; i<_vertices.size(); ++i)
276 _vertices[i]->edges().erase(
this);
283 g2o::BaseMultiEdge<D, E>::resize(size);
285 for(std::size_t i=0; i<_vertices.size(); ++i)
304 virtual bool read(std::istream& is)
313 virtual bool write(std::ostream& os)
const 330 using g2o::BaseMultiEdge<D, E>::_error;
331 using g2o::BaseMultiEdge<D, E>::_vertices;
336 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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.
BaseTebBinaryEdge()
Construct edge.
BaseTebMultiEdge()
Construct edge.
BaseTebUnaryEdge()
Construct edge.
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
virtual ~BaseTebMultiEdge()
Destruct edge.
ErrorVector & getError()
Compute and return error / cost value.
Config class for the teb_local_planner and its components.
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 write(std::ostream &os) const
Write values to an output stream.
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 two 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.
virtual ~BaseTebBinaryEdge()
Destruct edge.
const TebConfig * cfg_
Store TebConfig class for parameters.
virtual ~BaseTebUnaryEdge()
Destruct edge.
virtual bool read(std::istream &is)
Read values from input stream.
Base edge connecting a single vertex in the TEB optimization problem.