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/g2o_types/base_teb_edges.h>
00050 #include <teb_local_planner/teb_config.h>
00051 
00052 #include <cmath>
00053 
00054 namespace teb_local_planner
00055 {
00056 
00073 class EdgeKinematicsDiffDrive : public BaseTebBinaryEdge<2, double, VertexPose, VertexPose>
00074 {
00075 public:
00076   
00080   EdgeKinematicsDiffDrive()
00081   {
00082       this->setMeasurement(0.);
00083   }
00084   
00088   void computeError()
00089   {
00090     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsDiffDrive()");
00091     const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00092     const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00093     
00094     Eigen::Vector2d deltaS = conf2->position() - conf1->position();
00095 
00096     // non holonomic constraint
00097     _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );
00098 
00099     // positive-drive-direction constraint
00100     Eigen::Vector2d angle_vec ( cos(conf1->theta()), sin(conf1->theta()) );        
00101     _error[1] = penaltyBoundFromBelow(deltaS.dot(angle_vec), 0,0);
00102     // epsilon=0, otherwise it pushes the first bandpoints away from start
00103 
00104     ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeKinematicsDiffDrive::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
00105   }
00106 
00107 #ifdef USE_ANALYTIC_JACOBI
00108 #if 1
00109 
00112   void linearizeOplus()
00113   {
00114     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsDiffDrive()");
00115     const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00116     const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00117     
00118     Eigen::Vector2d deltaS = conf2->position() - conf1->position();
00119             
00120     double cos1 = cos(conf1->theta());
00121     double cos2 = cos(conf2->theta());
00122     double sin1 = sin(conf1->theta());
00123     double sin2 = sin(conf2->theta());
00124     double aux1 = sin1 + sin2;
00125     double aux2 = cos1 + cos2;
00126     
00127     double dd_error_1 = deltaS[0]*cos1;
00128     double dd_error_2 = deltaS[1]*sin1;
00129     double dd_dev = penaltyBoundFromBelowDerivative(dd_error_1+dd_error_2, 0,0);
00130     
00131     double dev_nh_abs = g2o::sign( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - 
00132               ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );
00133             
00134     // conf1
00135     _jacobianOplusXi(0,0) = aux1 * dev_nh_abs; // nh x1
00136     _jacobianOplusXi(0,1) = -aux2 * dev_nh_abs; // nh y1
00137     _jacobianOplusXi(1,0) = -cos1 * dd_dev; // drive-dir x1
00138     _jacobianOplusXi(1,1) = -sin1 * dd_dev; // drive-dir y1
00139     _jacobianOplusXi(0,2) = (-dd_error_2 - dd_error_1) * dev_nh_abs; // nh angle
00140     _jacobianOplusXi(1,2) = ( -sin1*deltaS[0] + cos1*deltaS[1] ) * dd_dev; // drive-dir angle1
00141     
00142     // conf2
00143     _jacobianOplusXj(0,0) = -aux1 * dev_nh_abs; // nh x2
00144     _jacobianOplusXj(0,1) = aux2 * dev_nh_abs; // nh y2
00145     _jacobianOplusXj(1,0) = cos1 * dd_dev; // drive-dir x2
00146     _jacobianOplusXj(1,1) = sin1 * dd_dev; // drive-dir y2
00147     _jacobianOplusXj(0,2) = (-sin2*deltaS[1] - cos2*deltaS[0]) * dev_nh_abs; // nh angle
00148     _jacobianOplusXj(1,2) = 0; // drive-dir angle1                                      
00149   }
00150 #endif
00151 #endif
00152       
00153 public:
00154   EIGEN_MAKE_ALIGNED_OPERATOR_NEW   
00155 };
00156 
00157 
00158 
00159 
00182 class EdgeKinematicsCarlike : public BaseTebBinaryEdge<2, double, VertexPose, VertexPose>
00183 {
00184 public:
00185   
00189   EdgeKinematicsCarlike()
00190   {
00191       this->setMeasurement(0.);
00192   }
00193   
00197   void computeError()
00198   {
00199     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsCarlike()");
00200     const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00201     const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00202     
00203     Eigen::Vector2d deltaS = conf2->position() - conf1->position();
00204 
00205     // non holonomic constraint
00206     _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );
00207 
00208     // limit minimum turning radius
00209     double angle_diff = g2o::normalize_theta( conf2->theta() - conf1->theta() );
00210     if (angle_diff == 0)
00211       _error[1] = 0; // straight line motion
00212     else if (cfg_->trajectory.exact_arc_length) // use exact computation of the radius
00213       _error[1] = penaltyBoundFromBelow(fabs(deltaS.norm()/(2*sin(angle_diff/2))), cfg_->robot.min_turning_radius, 0.0);
00214     else
00215       _error[1] = penaltyBoundFromBelow(deltaS.norm() / fabs(angle_diff), cfg_->robot.min_turning_radius, 0.0); 
00216     // This edge is not affected by the epsilon parameter, the user might add an exra margin to the min_turning_radius parameter.
00217     
00218     ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeKinematicsCarlike::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
00219   }
00220   
00221 public:
00222   EIGEN_MAKE_ALIGNED_OPERATOR_NEW   
00223 };
00224 
00225 
00226 
00227 
00228 } // end namespace
00229 
00230 #endif


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sat Jun 8 2019 20:21:34