vertex_timediff.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 VERTEX_TIMEDIFF_H
45 #define VERTEX_TIMEDIFF_H
46 
47 
48 #include "g2o/config.h"
49 #include "g2o/core/base_vertex.h"
50 #include "g2o/core/hyper_graph_action.h"
51 
52 #include <Eigen/Core>
53 
54 namespace teb_local_planner
55 {
56 
61 class VertexTimeDiff : public g2o::BaseVertex<1, double>
62 {
63 public:
64 
69  VertexTimeDiff(bool fixed = false)
70  {
72  setFixed(fixed);
73  }
74 
80  VertexTimeDiff(double dt, bool fixed = false)
81  {
82  _estimate = dt;
83  setFixed(fixed);
84  }
85 
91  inline double& dt() {return _estimate;}
92 
98  inline const double& dt() const {return _estimate;}
99 
103  virtual void setToOriginImpl() override
104  {
105  _estimate = 0.1;
106  }
107 
113  virtual void oplusImpl(const double* update) override
114  {
115  _estimate += *update;
116  }
117 
123  virtual bool read(std::istream& is) override
124  {
125  is >> _estimate;
126  return true;
127  }
128 
134  virtual bool write(std::ostream& os) const override
135  {
136  os << estimate();
137  return os.good();
138  }
139 
140  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
141 };
142 
143 }
144 
145 #endif
teb_local_planner::VertexTimeDiff::read
virtual bool read(std::istream &is) override
Read an estimate of from an input stream.
Definition: vertex_timediff.h:164
teb_local_planner::VertexTimeDiff::setToOriginImpl
virtual void setToOriginImpl() override
Set the underlying TimeDiff estimate to default.
Definition: vertex_timediff.h:144
teb_local_planner::VertexTimeDiff::VertexTimeDiff
VertexTimeDiff(bool fixed=false)
Default constructor.
Definition: vertex_timediff.h:110
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
teb_local_planner::VertexTimeDiff::write
virtual bool write(std::ostream &os) const override
Write the estimate to an output stream.
Definition: vertex_timediff.h:175
teb_local_planner::VertexTimeDiff::dt
double & dt()
Access the timediff value of the vertex.
Definition: vertex_timediff.h:132
teb_local_planner::VertexTimeDiff::oplusImpl
virtual void oplusImpl(const double *update) override
Define the update increment . A simple addition implements what we want.
Definition: vertex_timediff.h:154
teb_local_planner
Definition: distance_calculations.h:46


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15