Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043 #ifndef EDGE_OBSTACLE_H_
00044 #define EDGE_OBSTACLE_H_
00045
00046 #include <teb_local_planner/obstacles.h>
00047 #include <teb_local_planner/robot_footprint_model.h>
00048 #include <teb_local_planner/g2o_types/vertex_pose.h>
00049 #include <teb_local_planner/g2o_types/penalties.h>
00050 #include <teb_local_planner/teb_config.h>
00051
00052 #include "g2o/core/base_unary_edge.h"
00053
00054
00055 namespace teb_local_planner
00056 {
00057
00070 class EdgeObstacle : public g2o::BaseUnaryEdge<1, const Obstacle*, VertexPose>
00071 {
00072 public:
00073
00077 EdgeObstacle()
00078 {
00079 _measurement = NULL;
00080 _vertices[0] =NULL;
00081 }
00082
00089 virtual ~EdgeObstacle()
00090 {
00091 if(_vertices[0])
00092 _vertices[0]->edges().erase(this);
00093 }
00094
00098 void computeError()
00099 {
00100 ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeObstacle()");
00101 const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
00102
00103 double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement);
00104
00105 _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon);
00106
00107 ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeObstacle::computeError() _error[0]=%f\n",_error[0]);
00108 }
00109
00110 #ifdef USE_ANALYTIC_JACOBI
00111 #if 0
00112
00116 void linearizeOplus()
00117 {
00118 ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgePointObstacle()");
00119 const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
00120
00121 Eigen::Vector2d deltaS = *_measurement - bandpt->position();
00122 double angdiff = atan2(deltaS[1],deltaS[0])-bandpt->theta();
00123
00124 double dist_squared = deltaS.squaredNorm();
00125 double dist = sqrt(dist_squared);
00126
00127 double aux0 = sin(angdiff);
00128 double dev_left_border = penaltyBoundFromBelowDerivative(dist*fabs(aux0),cfg_->obstacles.min_obstacle_dist,cfg_->optim.penalty_epsilon);
00129
00130 if (dev_left_border==0)
00131 {
00132 _jacobianOplusXi( 0 , 0 ) = 0;
00133 _jacobianOplusXi( 0 , 1 ) = 0;
00134 _jacobianOplusXi( 0 , 2 ) = 0;
00135 return;
00136 }
00137
00138 double aux1 = -fabs(aux0) / dist;
00139 double dev_norm_x = deltaS[0]*aux1;
00140 double dev_norm_y = deltaS[1]*aux1;
00141
00142 double aux2 = cos(angdiff) * g2o::sign(aux0);
00143 double aux3 = aux2 / dist_squared;
00144 double dev_proj_x = aux3 * deltaS[1] * dist;
00145 double dev_proj_y = -aux3 * deltaS[0] * dist;
00146 double dev_proj_angle = -aux2;
00147
00148 _jacobianOplusXi( 0 , 0 ) = dev_left_border * ( dev_norm_x + dev_proj_x );
00149 _jacobianOplusXi( 0 , 1 ) = dev_left_border * ( dev_norm_y + dev_proj_y );
00150 _jacobianOplusXi( 0 , 2 ) = dev_left_border * dev_proj_angle;
00151 }
00152 #endif
00153 #endif
00154
00161 ErrorVector& getError()
00162 {
00163 computeError();
00164 return _error;
00165 }
00166
00170 virtual bool read(std::istream& is)
00171 {
00172
00173 return true;
00174 }
00175
00179 virtual bool write(std::ostream& os) const
00180 {
00181
00182 return os.good();
00183 }
00184
00189 void setObstacle(const Obstacle* obstacle)
00190 {
00191 _measurement = obstacle;
00192 }
00193
00198 void setRobotModel(const BaseRobotFootprintModel* robot_model)
00199 {
00200 robot_model_ = robot_model;
00201 }
00202
00207 void setTebConfig(const TebConfig& cfg)
00208 {
00209 cfg_ = &cfg;
00210 }
00211
00218 void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle)
00219 {
00220 cfg_ = &cfg;
00221 robot_model_ = robot_model;
00222 _measurement = obstacle;
00223 }
00224
00225 protected:
00226
00227 const TebConfig* cfg_;
00228 const BaseRobotFootprintModel* robot_model_;
00229
00230 public:
00231 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00232
00233 };
00234
00235
00236
00251 class EdgeInflatedObstacle : public g2o::BaseUnaryEdge<2, const Obstacle*, VertexPose>
00252 {
00253 public:
00254
00258 EdgeInflatedObstacle()
00259 {
00260 _measurement = NULL;
00261 _vertices[0] =NULL;
00262 }
00263
00270 virtual ~EdgeInflatedObstacle()
00271 {
00272 if(_vertices[0])
00273 _vertices[0]->edges().erase(this);
00274 }
00275
00279 void computeError()
00280 {
00281 ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeObstacle()");
00282 const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
00283
00284 double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement);
00285
00286 _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon);
00287 _error[1] = penaltyBoundFromBelow(dist, cfg_->obstacles.inflation_dist, 0.0);
00288
00289
00290 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeObstacle::computeError() _error[0]=%f, _error[1]=%f\n",_error[0], _error[1]);
00291 }
00292
00299 ErrorVector& getError()
00300 {
00301 computeError();
00302 return _error;
00303 }
00304
00308 virtual bool read(std::istream& is)
00309 {
00310
00311 return true;
00312 }
00313
00317 virtual bool write(std::ostream& os) const
00318 {
00319
00320 return os.good();
00321 }
00322
00327 void setObstacle(const Obstacle* obstacle)
00328 {
00329 _measurement = obstacle;
00330 }
00331
00336 void setRobotModel(const BaseRobotFootprintModel* robot_model)
00337 {
00338 robot_model_ = robot_model;
00339 }
00340
00345 void setTebConfig(const TebConfig& cfg)
00346 {
00347 cfg_ = &cfg;
00348 }
00349
00356 void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle)
00357 {
00358 cfg_ = &cfg;
00359 robot_model_ = robot_model;
00360 _measurement = obstacle;
00361 }
00362
00363 protected:
00364
00365 const TebConfig* cfg_;
00366 const BaseRobotFootprintModel* robot_model_;
00367
00368 public:
00369 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00370
00371 };
00372
00373
00374 }
00375
00376 #endif