edge_obstacle.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Notes:
37  * The following class is derived from a class defined by the
38  * g2o-framework. g2o is licensed under the terms of the BSD License.
39  * Refer to the base class source for detailed licensing information.
40  *
41  * Author: Christoph Rösmann
42  *********************************************************************/
43 #ifndef EDGE_OBSTACLE_H_
44 #define EDGE_OBSTACLE_H_
45 
52 
53 
54 
55 namespace teb_local_planner
56 {
57 
70 class EdgeObstacle : public BaseTebUnaryEdge<1, const Obstacle*, VertexPose>
71 {
72 public:
73 
78  {
79  _measurement = NULL;
80  }
81 
85  void computeError()
86  {
87  ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeObstacle()");
88  const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
89 
90  double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement);
91 
93 
94  ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeObstacle::computeError() _error[0]=%f\n",_error[0]);
95  }
96 
97 #ifdef USE_ANALYTIC_JACOBI
98 #if 0
99 
103  void linearizeOplus()
104  {
105  ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgePointObstacle()");
106  const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
107 
108  Eigen::Vector2d deltaS = *_measurement - bandpt->position();
109  double angdiff = atan2(deltaS[1],deltaS[0])-bandpt->theta();
110 
111  double dist_squared = deltaS.squaredNorm();
112  double dist = sqrt(dist_squared);
113 
114  double aux0 = sin(angdiff);
115  double dev_left_border = penaltyBoundFromBelowDerivative(dist*fabs(aux0),cfg_->obstacles.min_obstacle_dist,cfg_->optim.penalty_epsilon);
116 
117  if (dev_left_border==0)
118  {
119  _jacobianOplusXi( 0 , 0 ) = 0;
120  _jacobianOplusXi( 0 , 1 ) = 0;
121  _jacobianOplusXi( 0 , 2 ) = 0;
122  return;
123  }
124 
125  double aux1 = -fabs(aux0) / dist;
126  double dev_norm_x = deltaS[0]*aux1;
127  double dev_norm_y = deltaS[1]*aux1;
128 
129  double aux2 = cos(angdiff) * g2o::sign(aux0);
130  double aux3 = aux2 / dist_squared;
131  double dev_proj_x = aux3 * deltaS[1] * dist;
132  double dev_proj_y = -aux3 * deltaS[0] * dist;
133  double dev_proj_angle = -aux2;
134 
135  _jacobianOplusXi( 0 , 0 ) = dev_left_border * ( dev_norm_x + dev_proj_x );
136  _jacobianOplusXi( 0 , 1 ) = dev_left_border * ( dev_norm_y + dev_proj_y );
137  _jacobianOplusXi( 0 , 2 ) = dev_left_border * dev_proj_angle;
138  }
139 #endif
140 #endif
141 
146  void setObstacle(const Obstacle* obstacle)
147  {
148  _measurement = obstacle;
149  }
150 
155  void setRobotModel(const BaseRobotFootprintModel* robot_model)
156  {
157  robot_model_ = robot_model;
158  }
159 
166  void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle)
167  {
168  cfg_ = &cfg;
169  robot_model_ = robot_model;
170  _measurement = obstacle;
171  }
172 
173 protected:
174 
176 
177 public:
178  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
179 
180 };
181 
182 
183 
198 class EdgeInflatedObstacle : public BaseTebUnaryEdge<2, const Obstacle*, VertexPose>
199 {
200 public:
201 
206  {
207  _measurement = NULL;
208  }
209 
214  {
215  ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeObstacle()");
216  const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
217 
218  double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement);
219 
221  _error[1] = penaltyBoundFromBelow(dist, cfg_->obstacles.inflation_dist, 0.0);
222 
223 
224  ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeObstacle::computeError() _error[0]=%f, _error[1]=%f\n",_error[0], _error[1]);
225  }
226 
231  void setObstacle(const Obstacle* obstacle)
232  {
233  _measurement = obstacle;
234  }
235 
240  void setRobotModel(const BaseRobotFootprintModel* robot_model)
241  {
242  robot_model_ = robot_model;
243  }
244 
251  void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle)
252  {
253  cfg_ = &cfg;
254  robot_model_ = robot_model;
255  _measurement = obstacle;
256  }
257 
258 protected:
259 
261 
262 public:
263  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
264 
265 };
266 
267 
268 } // end namespace
269 
270 #endif
double penaltyBoundFromBelow(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var from below: .
Definition: penalties.h:107
const BaseRobotFootprintModel * robot_model_
Store pointer to robot_model.
PoseSE2 & pose()
Access the pose.
Definition: vertex_pose.h:126
void setRobotModel(const BaseRobotFootprintModel *robot_model)
Set pointer to the robot model.
double min_obstacle_dist
Minimum desired separation from obstacles.
Definition: teb_config.h:115
Config class for the teb_local_planner and its components.
Definition: teb_config.h:61
Abstract class that defines the interface for robot footprint/contour models.
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
const TebConfig * cfg_
Store TebConfig class for parameters.
void setRobotModel(const BaseRobotFootprintModel *robot_model)
Set pointer to the robot model.
void setObstacle(const Obstacle *obstacle)
Set pointer to associated obstacle for the underlying cost function.
Edge defining the cost function for keeping a minimum distance from obstacles.
Definition: edge_obstacle.h:70
void computeError()
Actual cost function.
void setObstacle(const Obstacle *obstacle)
Set pointer to associated obstacle for the underlying cost function.
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: vertex_pose.h:178
const BaseRobotFootprintModel * robot_model_
Store pointer to robot_model.
Edge defining the cost function for keeping a minimum distance from inflated obstacles.
#define ROS_ASSERT_MSG(cond,...)
void computeError()
Actual cost function.
Definition: edge_obstacle.h:85
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
double penaltyBoundFromBelowDerivative(const double &var, const double &a, const double &epsilon)
Derivative of the linear penalty function for bounding var from below: .
Definition: penalties.h:177
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
Definition: teb_config.h:140
Eigen::Vector2d & position()
Access the 2D position part.
Definition: vertex_pose.h:141
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
EdgeObstacle()
Construct edge.
Definition: edge_obstacle.h:77
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
Definition: vertex_pose.h:63
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
double inflation_dist
buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in ...
Definition: teb_config.h:116
Base edge connecting a single vertex in the TEB optimization problem.
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
Abstract class that defines the interface for modelling obstacles.
Definition: obstacles.h:67
def sign(number)
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const =0
Calculate the distance between the robot and an obstacle.


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 5 2019 19:25:10