edge_acceleration.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_ACCELERATION_H_
00045 #define EDGE_ACCELERATION_H_
00046 
00047 #include <teb_local_planner/g2o_types/vertex_pose.h>
00048 #include <teb_local_planner/g2o_types/vertex_timediff.h>
00049 #include <teb_local_planner/g2o_types/penalties.h>
00050 #include <teb_local_planner/teb_config.h>
00051 
00052 #include "g2o/core/base_multi_edge.h"
00053 
00054 
00055 namespace teb_local_planner
00056 {
00057 
00076 class EdgeAcceleration : public g2o::BaseMultiEdge<2, double>
00077 {
00078 public:
00079 
00083   EdgeAcceleration()
00084   {
00085     this->resize(5);
00086     _vertices[0]=_vertices[1]=_vertices[2]=_vertices[3]=_vertices[4]=NULL;
00087   }
00088   
00095   virtual ~EdgeAcceleration()
00096   {
00097     for(unsigned int i=0;i<5;i++)
00098     {
00099         if(_vertices[i])
00100           _vertices[i]->edges().erase(this);
00101     }
00102   }
00103    
00107   void computeError()
00108   {
00109     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()");
00110     const VertexPose* pose1 = static_cast<const VertexPose*>(_vertices[0]);
00111     const VertexPose* pose2 = static_cast<const VertexPose*>(_vertices[1]);
00112     const VertexPose* pose3 = static_cast<const VertexPose*>(_vertices[2]);
00113     const VertexTimeDiff* dt1 = static_cast<const VertexTimeDiff*>(_vertices[3]);
00114     const VertexTimeDiff* dt2 = static_cast<const VertexTimeDiff*>(_vertices[4]);
00115 
00116     // VELOCITY & ACCELERATION
00117     Eigen::Vector2d diff1 = pose2->position() - pose1->position();
00118     Eigen::Vector2d diff2 = pose3->position() - pose2->position();
00119     double vel1 = diff1.norm() / dt1->dt();
00120     double vel2 = diff2.norm() / dt2->dt();
00121     
00122     // consider directions
00123 //     vel1 *= g2o::sign(diff1[0]*cos(pose1->theta()) + diff1[1]*sin(pose1->theta())); 
00124 //     vel2 *= g2o::sign(diff2[0]*cos(pose2->theta()) + diff2[1]*sin(pose2->theta())); 
00125     vel1 *= fast_sigmoid( 100*(diff1.x()*cos(pose1->theta()) + diff1.y()*sin(pose1->theta())) ); 
00126     vel2 *= fast_sigmoid( 100*(diff2.x()*cos(pose2->theta()) + diff2.y()*sin(pose2->theta())) ); 
00127     
00128     double acc_lin  = (vel2 - vel1)*2 / ( dt1->dt() + dt2->dt() );
00129    
00130 
00131     _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00132     
00133     // ANGULAR ACCELERATION
00134     double omega1 = g2o::normalize_theta(pose2->theta() - pose1->theta()) / dt1->dt();
00135     double omega2 = g2o::normalize_theta(pose3->theta() - pose2->theta()) / dt2->dt();
00136     double acc_rot  = (omega2 - omega1)*2 / ( dt1->dt() + dt2->dt() );
00137       
00138     _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00139 
00140     
00141     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAcceleration::computeError() translational: _error[0]=%f\n",_error[0]);
00142     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAcceleration::computeError() rotational: _error[1]=%f\n",_error[1]);
00143   }
00144 
00145 
00146 
00147 #ifdef USE_ANALYTIC_JACOBI
00148 #if 0
00149   /*
00150    * @brief Jacobi matrix of the cost function specified in computeError().
00151    */
00152   void linearizeOplus()
00153   {
00154     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()");
00155     const VertexPointXY* conf1 = static_cast<const VertexPointXY*>(_vertices[0]);
00156     const VertexPointXY* conf2 = static_cast<const VertexPointXY*>(_vertices[1]);
00157     const VertexPointXY* conf3 = static_cast<const VertexPointXY*>(_vertices[2]);
00158     const VertexTimeDiff* deltaT1 = static_cast<const VertexTimeDiff*>(_vertices[3]);
00159     const VertexTimeDiff* deltaT2 = static_cast<const VertexTimeDiff*>(_vertices[4]);
00160     const VertexOrientation* angle1 = static_cast<const VertexOrientation*>(_vertices[5]);
00161     const VertexOrientation* angle2 = static_cast<const VertexOrientation*>(_vertices[6]);
00162     const VertexOrientation* angle3 = static_cast<const VertexOrientation*>(_vertices[7]);
00163 
00164     Eigen::Vector2d deltaS1 = conf2->estimate() - conf1->estimate();
00165     Eigen::Vector2d deltaS2 = conf3->estimate() - conf2->estimate();
00166     double dist1 = deltaS1.norm();
00167     double dist2 = deltaS2.norm();
00168     
00169     double sum_time = deltaT1->estimate() + deltaT2->estimate();
00170     double sum_time_inv = 1 / sum_time;
00171     double dt1_inv = 1/deltaT1->estimate();
00172     double dt2_inv = 1/deltaT2->estimate();
00173     double aux0 = 2/sum_time_inv;
00174     double aux1 = dist1 * deltaT1->estimate();
00175     double aux2 = dist2 * deltaT2->estimate();
00176 
00177     double vel1 = dist1 * dt1_inv;
00178     double vel2 = dist2 * dt2_inv;
00179     double omega1 = g2o::normalize_theta( angle2->estimate() - angle1->estimate() ) * dt1_inv;
00180     double omega2 = g2o::normalize_theta( angle3->estimate() - angle2->estimate() ) * dt2_inv;
00181     double acc = (vel2 - vel1) * aux0;
00182     double omegadot = (omega2 - omega1) * aux0;
00183     double aux3 = -acc/2;
00184     double aux4 = -omegadot/2;
00185     
00186     double dev_border_acc = penaltyBoundToIntervalDerivative(acc, tebConfig.robot_acceleration_max_trans,optimizationConfig.optimization_boundaries_epsilon,optimizationConfig.optimization_boundaries_scale,optimizationConfig.optimization_boundaries_order);
00187     double dev_border_omegadot = penaltyBoundToIntervalDerivative(omegadot, tebConfig.robot_acceleration_max_rot,optimizationConfig.optimization_boundaries_epsilon,optimizationConfig.optimization_boundaries_scale,optimizationConfig.optimization_boundaries_order);
00188     
00189     _jacobianOplus[0].resize(2,2); // conf1
00190     _jacobianOplus[1].resize(2,2); // conf2
00191     _jacobianOplus[2].resize(2,2); // conf3
00192     _jacobianOplus[3].resize(2,1); // deltaT1
00193     _jacobianOplus[4].resize(2,1); // deltaT2
00194     _jacobianOplus[5].resize(2,1); // angle1
00195     _jacobianOplus[6].resize(2,1); // angle2
00196     _jacobianOplus[7].resize(2,1); // angle3
00197     
00198     if (aux1==0) aux1=1e-20;
00199     if (aux2==0) aux2=1e-20;
00200   
00201     if (dev_border_acc!=0)
00202     {
00203       // TODO: double aux = aux0 * dev_border_acc;
00204       // double aux123 = aux / aux1;
00205       _jacobianOplus[0](0,0) = aux0 * deltaS1[0] / aux1 * dev_border_acc; // acc x1
00206       _jacobianOplus[0](0,1) = aux0 * deltaS1[1] / aux1 * dev_border_acc; // acc y1
00207       _jacobianOplus[1](0,0) = -aux0 * ( deltaS1[0] / aux1 + deltaS2[0] / aux2 ) * dev_border_acc; // acc x2
00208       _jacobianOplus[1](0,1) = -aux0 * ( deltaS1[1] / aux1 + deltaS2[1] / aux2 ) * dev_border_acc; // acc y2
00209       _jacobianOplus[2](0,0) = aux0 * deltaS2[0] / aux2 * dev_border_acc; // acc x3
00210       _jacobianOplus[2](0,1) = aux0 * deltaS2[1] / aux2 * dev_border_acc; // acc y3     
00211       _jacobianOplus[2](0,0) = 0;
00212       _jacobianOplus[2](0,1) = 0;
00213       _jacobianOplus[3](0,0) = aux0 * (aux3 + vel1 * dt1_inv) * dev_border_acc; // acc deltaT1
00214       _jacobianOplus[4](0,0) = aux0 * (aux3 - vel2 * dt2_inv) * dev_border_acc; // acc deltaT2
00215     }
00216     else
00217     {
00218       _jacobianOplus[0](0,0) = 0; // acc x1
00219       _jacobianOplus[0](0,1) = 0; // acc y1     
00220       _jacobianOplus[1](0,0) = 0; // acc x2
00221       _jacobianOplus[1](0,1) = 0; // acc y2
00222       _jacobianOplus[2](0,0) = 0; // acc x3
00223       _jacobianOplus[2](0,1) = 0; // acc y3     
00224       _jacobianOplus[3](0,0) = 0; // acc deltaT1
00225       _jacobianOplus[4](0,0) = 0; // acc deltaT2
00226     }
00227     
00228     if (dev_border_omegadot!=0)
00229     {
00230       _jacobianOplus[3](1,0) = aux0 * ( aux4 + omega1 * dt1_inv ) * dev_border_omegadot; // omegadot deltaT1
00231       _jacobianOplus[4](1,0) = aux0 * ( aux4 - omega2 * dt2_inv ) * dev_border_omegadot; // omegadot deltaT2
00232       _jacobianOplus[5](1,0) = aux0 * dt1_inv * dev_border_omegadot; // omegadot angle1
00233       _jacobianOplus[6](1,0) = -aux0 * ( dt1_inv + dt2_inv ) * dev_border_omegadot; // omegadot angle2
00234       _jacobianOplus[7](1,0) = aux0 * dt2_inv * dev_border_omegadot; // omegadot angle3
00235     }
00236     else
00237     {
00238       _jacobianOplus[3](1,0) = 0; // omegadot deltaT1
00239       _jacobianOplus[4](1,0) = 0; // omegadot deltaT2
00240       _jacobianOplus[5](1,0) = 0; // omegadot angle1
00241       _jacobianOplus[6](1,0) = 0; // omegadot angle2
00242       _jacobianOplus[7](1,0) = 0; // omegadot angle3                    
00243     }
00244 
00245     _jacobianOplus[0](1,0) = 0; // omegadot x1
00246     _jacobianOplus[0](1,1) = 0; // omegadot y1
00247     _jacobianOplus[1](1,0) = 0; // omegadot x2
00248     _jacobianOplus[1](1,1) = 0; // omegadot y2
00249     _jacobianOplus[2](1,0) = 0; // omegadot x3
00250     _jacobianOplus[2](1,1) = 0; // omegadot y3
00251     _jacobianOplus[5](0,0) = 0; // acc angle1
00252     _jacobianOplus[6](0,0) = 0; // acc angle2
00253     _jacobianOplus[7](0,0) = 0; // acc angle3
00254     }
00255 #endif
00256 #endif
00257         
00264   ErrorVector& getError()
00265   {
00266     computeError();
00267     return _error;
00268   }     
00269         
00273   bool read(std::istream& is)
00274   {
00275     is >> _measurement;
00276     is >> information()(0,0);   // TODO: fixme
00277     return true;
00278   }
00279 
00283   bool write(std::ostream& os) const
00284   {
00285     os << information()(0,0) << " Error: " << _error[0] << " " << _error[1]; // TODO: fixme
00286 
00287     return os.good();
00288   }
00289   
00294   void setTebConfig(const TebConfig& cfg)
00295   {
00296     cfg_ = &cfg;
00297   }
00298     
00299 protected:
00300       
00301   const TebConfig* cfg_; 
00302       
00303 public: 
00304   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00305    
00306 };
00307     
00308     
00328 class EdgeAccelerationStart : public g2o::BaseMultiEdge<2, const Eigen::Vector2d*>
00329 {
00330 public:
00331 
00335   EdgeAccelerationStart()
00336   {
00337     this->resize(3);
00338     _vertices[0]=_vertices[1]=_vertices[2]=NULL;
00339     _measurement = NULL;
00340   }
00341   
00348   ~EdgeAccelerationStart()
00349   {
00350     for(unsigned int i=0;i<3;i++)
00351     {
00352       if(_vertices[i]) 
00353         _vertices[i]->edges().erase(this);
00354     }
00355   }
00356   
00360   void computeError()
00361   {
00362     ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setStartVelocity() on EdgeAccelerationStart()");
00363     const VertexPose* pose1 = static_cast<const VertexPose*>(_vertices[0]);
00364     const VertexPose* pose2 = static_cast<const VertexPose*>(_vertices[1]);
00365     const VertexTimeDiff* dt = static_cast<const VertexTimeDiff*>(_vertices[2]);
00366 
00367     // VELOCITY & ACCELERATION
00368     Eigen::Vector2d diff = pose2->position() - pose1->position();
00369     double vel1 = _measurement->coeffRef(0);
00370     double vel2 = diff.norm() / dt->dt();
00371 
00372     // consider directions
00373     //vel2 *= g2o::sign(diff[0]*cos(pose1->theta()) + diff[1]*sin(pose1->theta())); 
00374     vel2 *= fast_sigmoid( 100*(diff.x()*cos(pose1->theta()) + diff.y()*sin(pose1->theta())) ); 
00375     
00376     double acc_lin  = (vel2 - vel1) / dt->dt();
00377     
00378     _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00379     
00380     // ANGULAR ACCELERATION
00381     double omega1 = _measurement->coeffRef(1);
00382     double omega2 = g2o::normalize_theta(pose2->theta() - pose1->theta()) / dt->dt();
00383     double acc_rot  = (omega2 - omega1) / dt->dt();
00384       
00385     _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00386 
00387     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationStart::computeError() translational: _error[0]=%f\n",_error[0]);
00388     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationStart::computeError() rotational: _error[1]=%f\n",_error[1]);
00389   }
00390 
00397   ErrorVector& getError()
00398   {
00399     computeError();
00400     return _error;
00401   }     
00402         
00406   bool read(std::istream& is)
00407   {
00408     is >> information()(0,0);   // TODO: fixme
00409     return true;
00410   }
00411 
00415   bool write(std::ostream& os) const
00416   {
00417     os << information()(0,0) << " Error: " << _error[0] << " " << _error[1]; // TODO: fixme
00418     return os.good();
00419   }
00420   
00425   void setInitialVelocity(const Eigen::Vector2d& vel_start)
00426   {
00427     _measurement = &vel_start;
00428   }
00429   
00430   
00435   void setTebConfig(const TebConfig& cfg)
00436   {
00437       cfg_ = &cfg;
00438   }
00439     
00440 protected:
00441       
00442   const TebConfig* cfg_; 
00443       
00444 public:       
00445   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00446 };    
00447     
00448     
00449     
00450 
00470 class EdgeAccelerationGoal : public g2o::BaseMultiEdge<2, const Eigen::Vector2d*>
00471 {
00472 public:
00473 
00477   EdgeAccelerationGoal()
00478   {
00479     _measurement = NULL;
00480     this->resize(3);
00481     _vertices[0]=_vertices[1]=_vertices[2]=NULL;
00482   }
00483   
00490   ~EdgeAccelerationGoal()
00491   {
00492     for(unsigned int i=0;i<3;i++)
00493     {
00494       if(_vertices[i])
00495         _vertices[i]->edges().erase(this);
00496     }
00497   }
00498 
00502   void computeError()
00503   {
00504     ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setGoalVelocity() on EdgeAccelerationGoal()");
00505     const VertexPose* pose_pre_goal = static_cast<const VertexPose*>(_vertices[0]);
00506     const VertexPose* pose_goal = static_cast<const VertexPose*>(_vertices[1]);
00507     const VertexTimeDiff* dt = static_cast<const VertexTimeDiff*>(_vertices[2]);
00508 
00509     // VELOCITY & ACCELERATION
00510 
00511     Eigen::Vector2d diff = pose_goal->position() - pose_pre_goal->position();    
00512     double vel1 = diff.norm() / dt->dt();
00513     double vel2 = _measurement->coeffRef(0);
00514     
00515     // consider directions
00516     //vel1 *= g2o::sign(diff[0]*cos(pose_pre_goal->theta()) + diff[1]*sin(pose_pre_goal->theta())); 
00517     vel1 *= fast_sigmoid( 100*(diff.x()*cos(pose_pre_goal->theta()) + diff.y()*sin(pose_pre_goal->theta())) ); 
00518     
00519     double acc_lin  = (vel2 - vel1) / dt->dt();
00520 
00521     _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00522     
00523     // ANGULAR ACCELERATION
00524     double omega1 = g2o::normalize_theta(pose_goal->theta() - pose_pre_goal->theta()) / dt->dt();
00525     double omega2 = _measurement->coeffRef(1);
00526     double acc_rot  = (omega2 - omega1) / dt->dt();
00527       
00528     _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00529 
00530     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationGoal::computeError() translational: _error[0]=%f\n",_error[0]);
00531     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationGoal::computeError() rotational: _error[1]=%f\n",_error[1]);
00532   }
00533   
00534   
00541   ErrorVector& getError()
00542   {
00543     computeError();
00544     return _error;
00545   }  
00546         
00547         
00551   bool read(std::istream& is)
00552   {
00553     is >> information()(0,0);   // TODO: fixme
00554     return true;
00555   }
00556 
00560   bool write(std::ostream& os) const
00561   {
00562     os << information()(0,0) << " Error: " << _error[0] << " " << _error[1]; // TODO: fixme
00563 
00564     return os.good();
00565   }
00566   
00567   
00572   void setGoalVelocity(const Eigen::Vector2d& vel_goal)
00573   {
00574     _measurement = &vel_goal;
00575   }
00576   
00581   void setTebConfig(const TebConfig& cfg)
00582   {
00583     cfg_ = &cfg;
00584   }
00585 
00586 protected:
00587 
00588   const TebConfig* cfg_; 
00589 
00590 public: 
00591   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00592 }; 
00593     
00594 
00595 }; // end namespace
00596 
00597 #endif /* EDGE_ACCELERATION_H_ */


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