edge_time_optimal.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 EDGE_TIMEOPTIMAL_H_
00045 #define EDGE_TIMEOPTIMAL_H_
00046 
00047 #include <float.h>
00048 
00049 #include <g2o/core/base_unary_edge.h>
00050 #include <base_local_planner/BaseLocalPlannerConfig.h>
00051 
00052 #include <teb_local_planner/g2o_types/vertex_timediff.h>
00053 #include <teb_local_planner/g2o_types/penalties.h>
00054 #include <teb_local_planner/teb_config.h>
00055 
00056 #include <Eigen/Core>
00057 
00058 namespace teb_local_planner
00059 {
00060 
00061   
00073 class EdgeTimeOptimal : public g2o::BaseUnaryEdge<1, double, VertexTimeDiff>
00074 {
00075 public:
00076                 
00080   EdgeTimeOptimal()
00081   {
00082     this->setMeasurement(0.);
00083     _vertices[0] = NULL;
00084   }
00085   
00092   virtual ~EdgeTimeOptimal()
00093   {
00094     if(_vertices[0]) 
00095       _vertices[0]->edges().erase(this); 
00096   }
00097 
00101   void computeError()
00102   {
00103     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeTimeOptimal()");
00104     const VertexTimeDiff* timediff = static_cast<const VertexTimeDiff*>(_vertices[0]);
00105 
00106    _error[0] = timediff->dt();
00107   
00108     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeTimeOptimal::computeError() _error[0]=%f\n",_error[0]);
00109   }
00110 
00111 #ifdef USE_ANALYTIC_JACOBI
00112 
00115   void linearizeOplus()
00116   {
00117     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeTimeOptimal()");
00118     _jacobianOplusXi( 0 , 0 ) = 1;
00119   }
00120 #endif
00121     
00128   ErrorVector& getError()
00129   {
00130     computeError();
00131     return _error;
00132   }
00133   
00137   virtual bool read(std::istream& is)
00138   {
00139     is >> _measurement;
00140     is >> information()(0,0);
00141     return true;
00142   }
00143 
00147   virtual bool write(std::ostream& os) const
00148   {
00149     os << information()(0,0) << " Error: " << _error[0]; 
00150     return os.good();
00151   }
00152     
00157   void setTebConfig(const TebConfig& cfg)
00158   {
00159     cfg_ = &cfg;
00160   }
00161 
00162 protected:
00163   
00164   const TebConfig* cfg_; 
00165   
00166 public:        
00167   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00168 };
00169 
00170 }; // end namespace
00171 
00172 #endif /* EDGE_TIMEOPTIMAL_H_ */


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:15