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 #include <teb_local_planner/g2o_types/base_teb_edges.h>
00052 
00053 #include <geometry_msgs/Twist.h>
00054 
00055 
00056 
00057 namespace teb_local_planner
00058 {
00059 
00078 class EdgeAcceleration : public BaseTebMultiEdge<2, double>
00079 {
00080 public:
00081 
00085   EdgeAcceleration()
00086   {
00087     this->resize(5);
00088   }
00089     
00093   void computeError()
00094   {
00095     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()");
00096     const VertexPose* pose1 = static_cast<const VertexPose*>(_vertices[0]);
00097     const VertexPose* pose2 = static_cast<const VertexPose*>(_vertices[1]);
00098     const VertexPose* pose3 = static_cast<const VertexPose*>(_vertices[2]);
00099     const VertexTimeDiff* dt1 = static_cast<const VertexTimeDiff*>(_vertices[3]);
00100     const VertexTimeDiff* dt2 = static_cast<const VertexTimeDiff*>(_vertices[4]);
00101 
00102     // VELOCITY & ACCELERATION
00103     const Eigen::Vector2d diff1 = pose2->position() - pose1->position();
00104     const Eigen::Vector2d diff2 = pose3->position() - pose2->position();
00105         
00106     double dist1 = diff1.norm();
00107     double dist2 = diff2.norm();
00108     const double angle_diff1 = g2o::normalize_theta(pose2->theta() - pose1->theta());
00109     const double angle_diff2 = g2o::normalize_theta(pose3->theta() - pose2->theta());
00110     
00111     if (cfg_->trajectory.exact_arc_length) // use exact arc length instead of Euclidean approximation
00112     {
00113         if (angle_diff1 != 0)
00114         {
00115             const double radius =  dist1/(2*sin(angle_diff1/2));
00116             dist1 = fabs( angle_diff1 * radius ); // actual arg length!
00117         }
00118         if (angle_diff2 != 0)
00119         {
00120             const double radius =  dist2/(2*sin(angle_diff2/2));
00121             dist2 = fabs( angle_diff2 * radius ); // actual arg length!
00122         }
00123     }
00124     
00125     double vel1 = dist1 / dt1->dt();
00126     double vel2 = dist2 / dt2->dt();
00127     
00128     
00129     // consider directions
00130 //     vel1 *= g2o::sign(diff1[0]*cos(pose1->theta()) + diff1[1]*sin(pose1->theta())); 
00131 //     vel2 *= g2o::sign(diff2[0]*cos(pose2->theta()) + diff2[1]*sin(pose2->theta())); 
00132     vel1 *= fast_sigmoid( 100*(diff1.x()*cos(pose1->theta()) + diff1.y()*sin(pose1->theta())) ); 
00133     vel2 *= fast_sigmoid( 100*(diff2.x()*cos(pose2->theta()) + diff2.y()*sin(pose2->theta())) ); 
00134     
00135     const double acc_lin  = (vel2 - vel1)*2 / ( dt1->dt() + dt2->dt() );
00136    
00137 
00138     _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00139     
00140     // ANGULAR ACCELERATION
00141     const double omega1 = angle_diff1 / dt1->dt();
00142     const double omega2 = angle_diff2 / dt2->dt();
00143     const double acc_rot  = (omega2 - omega1)*2 / ( dt1->dt() + dt2->dt() );
00144       
00145     _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00146 
00147     
00148     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAcceleration::computeError() translational: _error[0]=%f\n",_error[0]);
00149     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAcceleration::computeError() rotational: _error[1]=%f\n",_error[1]);
00150   }
00151 
00152 
00153 
00154 #ifdef USE_ANALYTIC_JACOBI
00155 #if 0
00156   /*
00157    * @brief Jacobi matrix of the cost function specified in computeError().
00158    */
00159   void linearizeOplus()
00160   {
00161     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()");
00162     const VertexPointXY* conf1 = static_cast<const VertexPointXY*>(_vertices[0]);
00163     const VertexPointXY* conf2 = static_cast<const VertexPointXY*>(_vertices[1]);
00164     const VertexPointXY* conf3 = static_cast<const VertexPointXY*>(_vertices[2]);
00165     const VertexTimeDiff* deltaT1 = static_cast<const VertexTimeDiff*>(_vertices[3]);
00166     const VertexTimeDiff* deltaT2 = static_cast<const VertexTimeDiff*>(_vertices[4]);
00167     const VertexOrientation* angle1 = static_cast<const VertexOrientation*>(_vertices[5]);
00168     const VertexOrientation* angle2 = static_cast<const VertexOrientation*>(_vertices[6]);
00169     const VertexOrientation* angle3 = static_cast<const VertexOrientation*>(_vertices[7]);
00170 
00171     Eigen::Vector2d deltaS1 = conf2->estimate() - conf1->estimate();
00172     Eigen::Vector2d deltaS2 = conf3->estimate() - conf2->estimate();
00173     double dist1 = deltaS1.norm();
00174     double dist2 = deltaS2.norm();
00175     
00176     double sum_time = deltaT1->estimate() + deltaT2->estimate();
00177     double sum_time_inv = 1 / sum_time;
00178     double dt1_inv = 1/deltaT1->estimate();
00179     double dt2_inv = 1/deltaT2->estimate();
00180     double aux0 = 2/sum_time_inv;
00181     double aux1 = dist1 * deltaT1->estimate();
00182     double aux2 = dist2 * deltaT2->estimate();
00183 
00184     double vel1 = dist1 * dt1_inv;
00185     double vel2 = dist2 * dt2_inv;
00186     double omega1 = g2o::normalize_theta( angle2->estimate() - angle1->estimate() ) * dt1_inv;
00187     double omega2 = g2o::normalize_theta( angle3->estimate() - angle2->estimate() ) * dt2_inv;
00188     double acc = (vel2 - vel1) * aux0;
00189     double omegadot = (omega2 - omega1) * aux0;
00190     double aux3 = -acc/2;
00191     double aux4 = -omegadot/2;
00192     
00193     double dev_border_acc = penaltyBoundToIntervalDerivative(acc, tebConfig.robot_acceleration_max_trans,optimizationConfig.optimization_boundaries_epsilon,optimizationConfig.optimization_boundaries_scale,optimizationConfig.optimization_boundaries_order);
00194     double dev_border_omegadot = penaltyBoundToIntervalDerivative(omegadot, tebConfig.robot_acceleration_max_rot,optimizationConfig.optimization_boundaries_epsilon,optimizationConfig.optimization_boundaries_scale,optimizationConfig.optimization_boundaries_order);
00195     
00196     _jacobianOplus[0].resize(2,2); // conf1
00197     _jacobianOplus[1].resize(2,2); // conf2
00198     _jacobianOplus[2].resize(2,2); // conf3
00199     _jacobianOplus[3].resize(2,1); // deltaT1
00200     _jacobianOplus[4].resize(2,1); // deltaT2
00201     _jacobianOplus[5].resize(2,1); // angle1
00202     _jacobianOplus[6].resize(2,1); // angle2
00203     _jacobianOplus[7].resize(2,1); // angle3
00204     
00205     if (aux1==0) aux1=1e-20;
00206     if (aux2==0) aux2=1e-20;
00207   
00208     if (dev_border_acc!=0)
00209     {
00210       // TODO: double aux = aux0 * dev_border_acc;
00211       // double aux123 = aux / aux1;
00212       _jacobianOplus[0](0,0) = aux0 * deltaS1[0] / aux1 * dev_border_acc; // acc x1
00213       _jacobianOplus[0](0,1) = aux0 * deltaS1[1] / aux1 * dev_border_acc; // acc y1
00214       _jacobianOplus[1](0,0) = -aux0 * ( deltaS1[0] / aux1 + deltaS2[0] / aux2 ) * dev_border_acc; // acc x2
00215       _jacobianOplus[1](0,1) = -aux0 * ( deltaS1[1] / aux1 + deltaS2[1] / aux2 ) * dev_border_acc; // acc y2
00216       _jacobianOplus[2](0,0) = aux0 * deltaS2[0] / aux2 * dev_border_acc; // acc x3
00217       _jacobianOplus[2](0,1) = aux0 * deltaS2[1] / aux2 * dev_border_acc; // acc y3     
00218       _jacobianOplus[2](0,0) = 0;
00219       _jacobianOplus[2](0,1) = 0;
00220       _jacobianOplus[3](0,0) = aux0 * (aux3 + vel1 * dt1_inv) * dev_border_acc; // acc deltaT1
00221       _jacobianOplus[4](0,0) = aux0 * (aux3 - vel2 * dt2_inv) * dev_border_acc; // acc deltaT2
00222     }
00223     else
00224     {
00225       _jacobianOplus[0](0,0) = 0; // acc x1
00226       _jacobianOplus[0](0,1) = 0; // acc y1     
00227       _jacobianOplus[1](0,0) = 0; // acc x2
00228       _jacobianOplus[1](0,1) = 0; // acc y2
00229       _jacobianOplus[2](0,0) = 0; // acc x3
00230       _jacobianOplus[2](0,1) = 0; // acc y3     
00231       _jacobianOplus[3](0,0) = 0; // acc deltaT1
00232       _jacobianOplus[4](0,0) = 0; // acc deltaT2
00233     }
00234     
00235     if (dev_border_omegadot!=0)
00236     {
00237       _jacobianOplus[3](1,0) = aux0 * ( aux4 + omega1 * dt1_inv ) * dev_border_omegadot; // omegadot deltaT1
00238       _jacobianOplus[4](1,0) = aux0 * ( aux4 - omega2 * dt2_inv ) * dev_border_omegadot; // omegadot deltaT2
00239       _jacobianOplus[5](1,0) = aux0 * dt1_inv * dev_border_omegadot; // omegadot angle1
00240       _jacobianOplus[6](1,0) = -aux0 * ( dt1_inv + dt2_inv ) * dev_border_omegadot; // omegadot angle2
00241       _jacobianOplus[7](1,0) = aux0 * dt2_inv * dev_border_omegadot; // omegadot angle3
00242     }
00243     else
00244     {
00245       _jacobianOplus[3](1,0) = 0; // omegadot deltaT1
00246       _jacobianOplus[4](1,0) = 0; // omegadot deltaT2
00247       _jacobianOplus[5](1,0) = 0; // omegadot angle1
00248       _jacobianOplus[6](1,0) = 0; // omegadot angle2
00249       _jacobianOplus[7](1,0) = 0; // omegadot angle3                    
00250     }
00251 
00252     _jacobianOplus[0](1,0) = 0; // omegadot x1
00253     _jacobianOplus[0](1,1) = 0; // omegadot y1
00254     _jacobianOplus[1](1,0) = 0; // omegadot x2
00255     _jacobianOplus[1](1,1) = 0; // omegadot y2
00256     _jacobianOplus[2](1,0) = 0; // omegadot x3
00257     _jacobianOplus[2](1,1) = 0; // omegadot y3
00258     _jacobianOplus[5](0,0) = 0; // acc angle1
00259     _jacobianOplus[6](0,0) = 0; // acc angle2
00260     _jacobianOplus[7](0,0) = 0; // acc angle3
00261     }
00262 #endif
00263 #endif
00264 
00265       
00266 public: 
00267   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00268    
00269 };
00270     
00271     
00291 class EdgeAccelerationStart : public BaseTebMultiEdge<2, const geometry_msgs::Twist*>
00292 {
00293 public:
00294 
00298   EdgeAccelerationStart()
00299   {
00300     _measurement = NULL;
00301     this->resize(3);
00302   }
00303   
00304   
00308   void computeError()
00309   {
00310     ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setStartVelocity() on EdgeAccelerationStart()");
00311     const VertexPose* pose1 = static_cast<const VertexPose*>(_vertices[0]);
00312     const VertexPose* pose2 = static_cast<const VertexPose*>(_vertices[1]);
00313     const VertexTimeDiff* dt = static_cast<const VertexTimeDiff*>(_vertices[2]);
00314 
00315     // VELOCITY & ACCELERATION
00316     const Eigen::Vector2d diff = pose2->position() - pose1->position();
00317     double dist = diff.norm();
00318     const double angle_diff = g2o::normalize_theta(pose2->theta() - pose1->theta());
00319     if (cfg_->trajectory.exact_arc_length && angle_diff != 0)
00320     {
00321         const double radius =  dist/(2*sin(angle_diff/2));
00322         dist = fabs( angle_diff * radius ); // actual arg length!
00323     }
00324     
00325     const double vel1 = _measurement->linear.x;
00326     double vel2 = dist / dt->dt();
00327 
00328     // consider directions
00329     //vel2 *= g2o::sign(diff[0]*cos(pose1->theta()) + diff[1]*sin(pose1->theta())); 
00330     vel2 *= fast_sigmoid( 100*(diff.x()*cos(pose1->theta()) + diff.y()*sin(pose1->theta())) ); 
00331     
00332     const double acc_lin  = (vel2 - vel1) / dt->dt();
00333     
00334     _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00335     
00336     // ANGULAR ACCELERATION
00337     const double omega1 = _measurement->angular.z;
00338     const double omega2 = angle_diff / dt->dt();
00339     const double acc_rot  = (omega2 - omega1) / dt->dt();
00340       
00341     _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00342 
00343     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationStart::computeError() translational: _error[0]=%f\n",_error[0]);
00344     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationStart::computeError() rotational: _error[1]=%f\n",_error[1]);
00345   }
00346   
00351   void setInitialVelocity(const geometry_msgs::Twist& vel_start)
00352   {
00353     _measurement = &vel_start;
00354   }
00355   
00356 public:       
00357   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00358 };    
00359     
00360     
00361     
00362 
00382 class EdgeAccelerationGoal : public BaseTebMultiEdge<2, const geometry_msgs::Twist*>
00383 {
00384 public:
00385 
00389   EdgeAccelerationGoal()
00390   {
00391     _measurement = NULL;
00392     this->resize(3);
00393   }
00394   
00395 
00399   void computeError()
00400   {
00401     ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setGoalVelocity() on EdgeAccelerationGoal()");
00402     const VertexPose* pose_pre_goal = static_cast<const VertexPose*>(_vertices[0]);
00403     const VertexPose* pose_goal = static_cast<const VertexPose*>(_vertices[1]);
00404     const VertexTimeDiff* dt = static_cast<const VertexTimeDiff*>(_vertices[2]);
00405 
00406     // VELOCITY & ACCELERATION
00407 
00408     const Eigen::Vector2d diff = pose_goal->position() - pose_pre_goal->position();  
00409     double dist = diff.norm();
00410     const double angle_diff = g2o::normalize_theta(pose_goal->theta() - pose_pre_goal->theta());
00411     if (cfg_->trajectory.exact_arc_length  && angle_diff != 0)
00412     {
00413         double radius =  dist/(2*sin(angle_diff/2));
00414         dist = fabs( angle_diff * radius ); // actual arg length!
00415     }
00416     
00417     double vel1 = dist / dt->dt();
00418     const double vel2 = _measurement->linear.x;
00419     
00420     // consider directions
00421     //vel1 *= g2o::sign(diff[0]*cos(pose_pre_goal->theta()) + diff[1]*sin(pose_pre_goal->theta())); 
00422     vel1 *= fast_sigmoid( 100*(diff.x()*cos(pose_pre_goal->theta()) + diff.y()*sin(pose_pre_goal->theta())) ); 
00423     
00424     const double acc_lin  = (vel2 - vel1) / dt->dt();
00425 
00426     _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00427     
00428     // ANGULAR ACCELERATION
00429     const double omega1 = angle_diff / dt->dt();
00430     const double omega2 = _measurement->angular.z;
00431     const double acc_rot  = (omega2 - omega1) / dt->dt();
00432       
00433     _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00434 
00435     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationGoal::computeError() translational: _error[0]=%f\n",_error[0]);
00436     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationGoal::computeError() rotational: _error[1]=%f\n",_error[1]);
00437   }
00438     
00443   void setGoalVelocity(const geometry_msgs::Twist& vel_goal)
00444   {
00445     _measurement = &vel_goal;
00446   }
00447   
00448 public: 
00449   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00450 }; 
00451     
00452 
00453 
00454 
00474 class EdgeAccelerationHolonomic : public BaseTebMultiEdge<3, double>
00475 {
00476 public:
00477 
00481   EdgeAccelerationHolonomic()
00482   {
00483     this->resize(5);
00484   }
00485     
00489   void computeError()
00490   {
00491     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()");
00492     const VertexPose* pose1 = static_cast<const VertexPose*>(_vertices[0]);
00493     const VertexPose* pose2 = static_cast<const VertexPose*>(_vertices[1]);
00494     const VertexPose* pose3 = static_cast<const VertexPose*>(_vertices[2]);
00495     const VertexTimeDiff* dt1 = static_cast<const VertexTimeDiff*>(_vertices[3]);
00496     const VertexTimeDiff* dt2 = static_cast<const VertexTimeDiff*>(_vertices[4]);
00497 
00498     // VELOCITY & ACCELERATION
00499     Eigen::Vector2d diff1 = pose2->position() - pose1->position();
00500     Eigen::Vector2d diff2 = pose3->position() - pose2->position();
00501     
00502     double cos_theta1 = std::cos(pose1->theta());
00503     double sin_theta1 = std::sin(pose1->theta()); 
00504     double cos_theta2 = std::cos(pose2->theta());
00505     double sin_theta2 = std::sin(pose2->theta()); 
00506     
00507     // transform pose2 into robot frame pose1 (inverse 2d rotation matrix)
00508     double p1_dx =  cos_theta1*diff1.x() + sin_theta1*diff1.y();
00509     double p1_dy = -sin_theta1*diff1.x() + cos_theta1*diff1.y();
00510     // transform pose3 into robot frame pose2 (inverse 2d rotation matrix)
00511     double p2_dx =  cos_theta2*diff2.x() + sin_theta2*diff2.y();
00512     double p2_dy = -sin_theta2*diff2.x() + cos_theta2*diff2.y();
00513     
00514     double vel1_x = p1_dx / dt1->dt();
00515     double vel1_y = p1_dy / dt1->dt();
00516     double vel2_x = p2_dx / dt2->dt();
00517     double vel2_y = p2_dy / dt2->dt();
00518     
00519     double dt12 = dt1->dt() + dt2->dt();
00520     
00521     double acc_x  = (vel2_x - vel1_x)*2 / dt12;
00522     double acc_y  = (vel2_y - vel1_y)*2 / dt12;
00523    
00524     _error[0] = penaltyBoundToInterval(acc_x,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00525     _error[1] = penaltyBoundToInterval(acc_y,cfg_->robot.acc_lim_y,cfg_->optim.penalty_epsilon);
00526     
00527     // ANGULAR ACCELERATION
00528     double omega1 = g2o::normalize_theta(pose2->theta() - pose1->theta()) / dt1->dt();
00529     double omega2 = g2o::normalize_theta(pose3->theta() - pose2->theta()) / dt2->dt();
00530     double acc_rot  = (omega2 - omega1)*2 / dt12;
00531       
00532     _error[2] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00533 
00534     
00535     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAcceleration::computeError() translational: _error[0]=%f\n",_error[0]);
00536     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAcceleration::computeError() strafing: _error[1]=%f\n",_error[1]);
00537     ROS_ASSERT_MSG(std::isfinite(_error[2]), "EdgeAcceleration::computeError() rotational: _error[2]=%f\n",_error[2]);
00538   }
00539 
00540 public: 
00541   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00542    
00543 };
00544 
00545 
00566 class EdgeAccelerationHolonomicStart : public BaseTebMultiEdge<3, const geometry_msgs::Twist*>
00567 {
00568 public:
00569 
00573   EdgeAccelerationHolonomicStart()
00574   {
00575     this->resize(3);
00576     _measurement = NULL;
00577   }
00578     
00582   void computeError()
00583   {
00584     ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setStartVelocity() on EdgeAccelerationStart()");
00585     const VertexPose* pose1 = static_cast<const VertexPose*>(_vertices[0]);
00586     const VertexPose* pose2 = static_cast<const VertexPose*>(_vertices[1]);
00587     const VertexTimeDiff* dt = static_cast<const VertexTimeDiff*>(_vertices[2]);
00588 
00589     // VELOCITY & ACCELERATION
00590     Eigen::Vector2d diff = pose2->position() - pose1->position();
00591             
00592     double cos_theta1 = std::cos(pose1->theta());
00593     double sin_theta1 = std::sin(pose1->theta()); 
00594     
00595     // transform pose2 into robot frame pose1 (inverse 2d rotation matrix)
00596     double p1_dx =  cos_theta1*diff.x() + sin_theta1*diff.y();
00597     double p1_dy = -sin_theta1*diff.x() + cos_theta1*diff.y();
00598     
00599     double vel1_x = _measurement->linear.x;
00600     double vel1_y = _measurement->linear.y;
00601     double vel2_x = p1_dx / dt->dt();
00602     double vel2_y = p1_dy / dt->dt();
00603 
00604     double acc_lin_x  = (vel2_x - vel1_x) / dt->dt();
00605     double acc_lin_y  = (vel2_y - vel1_y) / dt->dt();
00606     
00607     _error[0] = penaltyBoundToInterval(acc_lin_x,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00608     _error[1] = penaltyBoundToInterval(acc_lin_y,cfg_->robot.acc_lim_y,cfg_->optim.penalty_epsilon);
00609     
00610     // ANGULAR ACCELERATION
00611     double omega1 = _measurement->angular.z;
00612     double omega2 = g2o::normalize_theta(pose2->theta() - pose1->theta()) / dt->dt();
00613     double acc_rot  = (omega2 - omega1) / dt->dt();
00614       
00615     _error[2] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00616 
00617     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationStart::computeError() translational: _error[0]=%f\n",_error[0]);
00618     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationStart::computeError() strafing: _error[1]=%f\n",_error[1]);
00619     ROS_ASSERT_MSG(std::isfinite(_error[2]), "EdgeAccelerationStart::computeError() rotational: _error[2]=%f\n",_error[2]);
00620   }
00621   
00626   void setInitialVelocity(const geometry_msgs::Twist& vel_start)
00627   {
00628     _measurement = &vel_start;
00629   }
00630         
00631 public:       
00632   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00633 };    
00634     
00635        
00636 
00657 class EdgeAccelerationHolonomicGoal : public BaseTebMultiEdge<3, const geometry_msgs::Twist*>
00658 {
00659 public:
00660 
00664   EdgeAccelerationHolonomicGoal()
00665   {
00666     _measurement = NULL;
00667     this->resize(3);
00668   }
00669   
00673   void computeError()
00674   {
00675     ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setGoalVelocity() on EdgeAccelerationGoal()");
00676     const VertexPose* pose_pre_goal = static_cast<const VertexPose*>(_vertices[0]);
00677     const VertexPose* pose_goal = static_cast<const VertexPose*>(_vertices[1]);
00678     const VertexTimeDiff* dt = static_cast<const VertexTimeDiff*>(_vertices[2]);
00679 
00680     // VELOCITY & ACCELERATION
00681 
00682     Eigen::Vector2d diff = pose_goal->position() - pose_pre_goal->position();    
00683     
00684     double cos_theta1 = std::cos(pose_pre_goal->theta());
00685     double sin_theta1 = std::sin(pose_pre_goal->theta()); 
00686     
00687     // transform pose2 into robot frame pose1 (inverse 2d rotation matrix)
00688     double p1_dx =  cos_theta1*diff.x() + sin_theta1*diff.y();
00689     double p1_dy = -sin_theta1*diff.x() + cos_theta1*diff.y();
00690    
00691     double vel1_x = p1_dx / dt->dt();
00692     double vel1_y = p1_dy / dt->dt();
00693     double vel2_x = _measurement->linear.x;
00694     double vel2_y = _measurement->linear.y;
00695     
00696     double acc_lin_x  = (vel2_x - vel1_x) / dt->dt();
00697     double acc_lin_y  = (vel2_y - vel1_y) / dt->dt();
00698 
00699     _error[0] = penaltyBoundToInterval(acc_lin_x,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
00700     _error[1] = penaltyBoundToInterval(acc_lin_y,cfg_->robot.acc_lim_y,cfg_->optim.penalty_epsilon);
00701     
00702     // ANGULAR ACCELERATION
00703     double omega1 = g2o::normalize_theta(pose_goal->theta() - pose_pre_goal->theta()) / dt->dt();
00704     double omega2 = _measurement->angular.z;
00705     double acc_rot  = (omega2 - omega1) / dt->dt();
00706       
00707     _error[2] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);
00708 
00709     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationGoal::computeError() translational: _error[0]=%f\n",_error[0]);
00710     ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationGoal::computeError() strafing: _error[1]=%f\n",_error[1]);
00711     ROS_ASSERT_MSG(std::isfinite(_error[2]), "EdgeAccelerationGoal::computeError() rotational: _error[2]=%f\n",_error[2]);
00712   }
00713   
00714   
00719   void setGoalVelocity(const geometry_msgs::Twist& vel_goal)
00720   {
00721     _measurement = &vel_goal;
00722   }
00723   
00724 
00725 public: 
00726   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00727 }; 
00728     
00729 
00730 
00731 
00732 }; // end namespace
00733 
00734 #endif /* EDGE_ACCELERATION_H_ */


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