edge_kinematics.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_KINEMATICS_H
00045 #define _EDGE_KINEMATICS_H
00046 
00047 #include <teb_local_planner/g2o_types/vertex_pose.h>
00048 #include <teb_local_planner/g2o_types/penalties.h>
00049 #include <teb_local_planner/teb_config.h>
00050 
00051 #include "g2o/core/base_binary_edge.h"
00052 
00053 #include <cmath>
00054 
00055 namespace teb_local_planner
00056 {
00057 
00074 class EdgeKinematicsDiffDrive : public g2o::BaseBinaryEdge<2, double, VertexPose, VertexPose>
00075 {
00076 public:
00077   
00081   EdgeKinematicsDiffDrive()
00082   {
00083       this->setMeasurement(0.);
00084       _vertices[0] = _vertices[1] = NULL;
00085   }
00086   
00093   virtual ~EdgeKinematicsDiffDrive()
00094   {
00095     for(unsigned int i=0;i<2;i++) 
00096     {
00097       if(_vertices[i])
00098         _vertices[i]->edges().erase(this);
00099     }
00100   }
00101 
00105   void computeError()
00106   {
00107     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsDiffDrive()");
00108     const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00109     const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00110     
00111     Eigen::Vector2d deltaS = conf2->position() - conf1->position();
00112 
00113     // non holonomic constraint
00114     _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );
00115 
00116     // positive-drive-direction constraint
00117     Eigen::Vector2d angle_vec ( cos(conf1->theta()), sin(conf1->theta()) );        
00118     _error[1] = penaltyBoundFromBelow(deltaS.dot(angle_vec), 0,0);
00119     // epsilon=0, otherwise it pushes the first bandpoints away from start
00120 
00121     ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeKinematicsDiffDrive::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
00122   }
00123 
00124 #ifdef USE_ANALYTIC_JACOBI
00125 #if 1
00126 
00129   void linearizeOplus()
00130   {
00131     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsDiffDrive()");
00132     const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00133     const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00134     
00135     Eigen::Vector2d deltaS = conf2->position() - conf1->position();
00136             
00137     double cos1 = cos(conf1->theta());
00138     double cos2 = cos(conf2->theta());
00139     double sin1 = sin(conf1->theta());
00140     double sin2 = sin(conf2->theta());
00141     double aux1 = sin1 + sin2;
00142     double aux2 = cos1 + cos2;
00143     
00144     double dd_error_1 = deltaS[0]*cos1;
00145     double dd_error_2 = deltaS[1]*sin1;
00146     double dd_dev = penaltyBoundFromBelowDerivative(dd_error_1+dd_error_2, 0,0);
00147     
00148     double dev_nh_abs = g2o::sign( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - 
00149               ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );
00150             
00151     // conf1
00152     _jacobianOplusXi(0,0) = aux1 * dev_nh_abs; // nh x1
00153     _jacobianOplusXi(0,1) = -aux2 * dev_nh_abs; // nh y1
00154     _jacobianOplusXi(1,0) = -cos1 * dd_dev; // drive-dir x1
00155     _jacobianOplusXi(1,1) = -sin1 * dd_dev; // drive-dir y1
00156     _jacobianOplusXi(0,2) = (-dd_error_2 - dd_error_1) * dev_nh_abs; // nh angle
00157     _jacobianOplusXi(1,2) = ( -sin1*deltaS[0] + cos1*deltaS[1] ) * dd_dev; // drive-dir angle1
00158     
00159     // conf2
00160     _jacobianOplusXj(0,0) = -aux1 * dev_nh_abs; // nh x2
00161     _jacobianOplusXj(0,1) = aux2 * dev_nh_abs; // nh y2
00162     _jacobianOplusXj(1,0) = cos1 * dd_dev; // drive-dir x2
00163     _jacobianOplusXj(1,1) = sin1 * dd_dev; // drive-dir y2
00164     _jacobianOplusXj(0,2) = (-sin2*deltaS[1] - cos2*deltaS[0]) * dev_nh_abs; // nh angle
00165     _jacobianOplusXj(1,2) = 0; // drive-dir angle1                                      
00166   }
00167 #endif
00168 #endif
00169     
00176   ErrorVector& getError()
00177   {
00178     computeError();
00179     return _error;
00180   }
00181 
00185   virtual bool read(std::istream& is)
00186   {
00187     is >> _measurement;
00188     //inverseMeasurement() = measurement() * -1;
00189     is >> information()(0,0);
00190     return true;
00191   }
00192 
00196   virtual bool write(std::ostream& os) const
00197   {
00198     //os << measurement() << " ";
00199     os << information()(0,0) << " Error NH-Constraint: " << _error[0] << ", Error PosDriveDir: " << _error[1];
00200     return os.good();
00201   }
00202 
00207   void setTebConfig(const TebConfig& cfg)
00208   {
00209     cfg_ = &cfg;
00210   }
00211 
00212 protected:
00213   
00214   const TebConfig* cfg_; 
00215   
00216 public:
00217   EIGEN_MAKE_ALIGNED_OPERATOR_NEW   
00218 };
00219 
00220 
00221 
00222 
00245 class EdgeKinematicsCarlike : public g2o::BaseBinaryEdge<2, double, VertexPose, VertexPose>
00246 {
00247 public:
00248   
00252   EdgeKinematicsCarlike()
00253   {
00254       this->setMeasurement(0.);
00255       _vertices[0] = _vertices[1] = NULL;
00256   }
00257   
00264   virtual ~EdgeKinematicsCarlike()
00265   {
00266     for(unsigned int i=0;i<2;i++) 
00267     {
00268       if(_vertices[i])
00269         _vertices[i]->edges().erase(this);
00270     }
00271   }
00272 
00276   void computeError()
00277   {
00278     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsCarlike()");
00279     const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00280     const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00281     
00282     Eigen::Vector2d deltaS = conf2->position() - conf1->position();
00283 
00284     // non holonomic constraint
00285     _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );
00286 
00287     // limit minimum turning radius
00288     double omega_t = g2o::normalize_theta( conf2->theta() - conf1->theta() );
00289     if (omega_t == 0)
00290       _error[1] = 0; // straight line motion
00291     else
00292       _error[1] = penaltyBoundFromBelow(deltaS.norm() / fabs(omega_t), cfg_->robot.min_turning_radius, 0.0); 
00293     // This edge is not affected by the epsilon parameter, the user might add an exra margin to the min_turning_radius parameter.
00294     
00295 
00296     ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeKinematicsCarlike::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
00297   }
00298     
00305   ErrorVector& getError()
00306   {
00307     computeError();
00308     return _error;
00309   }
00310 
00314   virtual bool read(std::istream& is)
00315   {
00316     is >> _measurement;
00317     //inverseMeasurement() = measurement() * -1;
00318     is >> information()(0,0);
00319     return true;
00320   }
00321 
00325   virtual bool write(std::ostream& os) const
00326   {
00327     //os << measurement() << " ";
00328     os << information()(0,0) << " Error NH-Constraint: " << _error[0] << ", Error PosDriveDir: " << _error[1];
00329     return os.good();
00330   }
00331 
00336   void setTebConfig(const TebConfig& cfg)
00337   {
00338     cfg_ = &cfg;
00339   }
00340 
00341 protected:
00342   
00343   const TebConfig* cfg_; 
00344   
00345 public:
00346   EIGEN_MAKE_ALIGNED_OPERATOR_NEW   
00347 };
00348 
00349 
00350 
00351 
00352 } // end namespace
00353 
00354 #endif


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