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/base_teb_edges.h>
00050 #include <teb_local_planner/g2o_types/penalties.h>
00051 #include <teb_local_planner/teb_config.h>
00052
00053
00054
00055 namespace teb_local_planner
00056 {
00057
00070 class EdgeObstacle : public BaseTebUnaryEdge<1, const Obstacle*, VertexPose>
00071 {
00072 public:
00073
00077 EdgeObstacle()
00078 {
00079 _measurement = NULL;
00080 }
00081
00085 void computeError()
00086 {
00087 ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeObstacle()");
00088 const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
00089
00090 double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement);
00091
00092 _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon);
00093
00094 ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeObstacle::computeError() _error[0]=%f\n",_error[0]);
00095 }
00096
00097 #ifdef USE_ANALYTIC_JACOBI
00098 #if 0
00099
00103 void linearizeOplus()
00104 {
00105 ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgePointObstacle()");
00106 const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
00107
00108 Eigen::Vector2d deltaS = *_measurement - bandpt->position();
00109 double angdiff = atan2(deltaS[1],deltaS[0])-bandpt->theta();
00110
00111 double dist_squared = deltaS.squaredNorm();
00112 double dist = sqrt(dist_squared);
00113
00114 double aux0 = sin(angdiff);
00115 double dev_left_border = penaltyBoundFromBelowDerivative(dist*fabs(aux0),cfg_->obstacles.min_obstacle_dist,cfg_->optim.penalty_epsilon);
00116
00117 if (dev_left_border==0)
00118 {
00119 _jacobianOplusXi( 0 , 0 ) = 0;
00120 _jacobianOplusXi( 0 , 1 ) = 0;
00121 _jacobianOplusXi( 0 , 2 ) = 0;
00122 return;
00123 }
00124
00125 double aux1 = -fabs(aux0) / dist;
00126 double dev_norm_x = deltaS[0]*aux1;
00127 double dev_norm_y = deltaS[1]*aux1;
00128
00129 double aux2 = cos(angdiff) * g2o::sign(aux0);
00130 double aux3 = aux2 / dist_squared;
00131 double dev_proj_x = aux3 * deltaS[1] * dist;
00132 double dev_proj_y = -aux3 * deltaS[0] * dist;
00133 double dev_proj_angle = -aux2;
00134
00135 _jacobianOplusXi( 0 , 0 ) = dev_left_border * ( dev_norm_x + dev_proj_x );
00136 _jacobianOplusXi( 0 , 1 ) = dev_left_border * ( dev_norm_y + dev_proj_y );
00137 _jacobianOplusXi( 0 , 2 ) = dev_left_border * dev_proj_angle;
00138 }
00139 #endif
00140 #endif
00141
00146 void setObstacle(const Obstacle* obstacle)
00147 {
00148 _measurement = obstacle;
00149 }
00150
00155 void setRobotModel(const BaseRobotFootprintModel* robot_model)
00156 {
00157 robot_model_ = robot_model;
00158 }
00159
00166 void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle)
00167 {
00168 cfg_ = &cfg;
00169 robot_model_ = robot_model;
00170 _measurement = obstacle;
00171 }
00172
00173 protected:
00174
00175 const BaseRobotFootprintModel* robot_model_;
00176
00177 public:
00178 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00179
00180 };
00181
00182
00183
00198 class EdgeInflatedObstacle : public BaseTebUnaryEdge<2, const Obstacle*, VertexPose>
00199 {
00200 public:
00201
00205 EdgeInflatedObstacle()
00206 {
00207 _measurement = NULL;
00208 }
00209
00213 void computeError()
00214 {
00215 ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeObstacle()");
00216 const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
00217
00218 double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement);
00219
00220 _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon);
00221 _error[1] = penaltyBoundFromBelow(dist, cfg_->obstacles.inflation_dist, 0.0);
00222
00223
00224 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeObstacle::computeError() _error[0]=%f, _error[1]=%f\n",_error[0], _error[1]);
00225 }
00226
00231 void setObstacle(const Obstacle* obstacle)
00232 {
00233 _measurement = obstacle;
00234 }
00235
00240 void setRobotModel(const BaseRobotFootprintModel* robot_model)
00241 {
00242 robot_model_ = robot_model;
00243 }
00244
00251 void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle)
00252 {
00253 cfg_ = &cfg;
00254 robot_model_ = robot_model;
00255 _measurement = obstacle;
00256 }
00257
00258 protected:
00259
00260 const BaseRobotFootprintModel* robot_model_;
00261
00262 public:
00263 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00264
00265 };
00266
00267
00268 }
00269
00270 #endif