edge_velocity_obstacle_ratio.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  *********************************************************************/
42 
43 #pragma once
44 
49 
50 namespace teb_local_planner
51 {
52 
53 
66 class EdgeVelocityObstacleRatio : public BaseTebMultiEdge<2, const Obstacle*>
67 {
68 public:
69 
74  robot_model_(nullptr)
75  {
76  // The three vertices are two poses and one time difference
77  this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices
78  }
79 
83  void computeError()
84  {
85  ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeVelocityObstacleRatio()");
86  const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
87  const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
88  const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
89 
90  const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position();
91 
92  double dist = deltaS.norm();
93  const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta());
94  if (cfg_->trajectory.exact_arc_length && angle_diff != 0)
95  {
96  double radius = dist/(2*sin(angle_diff/2));
97  dist = fabs( angle_diff * radius ); // actual arg length!
98  }
99  double vel = dist / deltaT->estimate();
100 
101  vel *= fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) ); // consider direction
102 
103  const double omega = angle_diff / deltaT->estimate();
104 
105  double dist_to_obstacle = robot_model_->calculateDistance(conf1->pose(), _measurement);
106 
107  double ratio;
108  if (dist_to_obstacle < cfg_->obstacles.obstacle_proximity_lower_bound)
109  ratio = 0;
110  else if (dist_to_obstacle > cfg_->obstacles.obstacle_proximity_upper_bound)
111  ratio = 1;
112  else
113  ratio = (dist_to_obstacle - cfg_->obstacles.obstacle_proximity_lower_bound) /
116 
117  const double max_vel_fwd = ratio * cfg_->robot.max_vel_x;
118  const double max_omega = ratio * cfg_->robot.max_vel_theta;
119  _error[0] = penaltyBoundToInterval(vel, max_vel_fwd, 0);
120  _error[1] = penaltyBoundToInterval(omega, max_omega, 0);
121 
122  ROS_ASSERT_MSG(std::isfinite(_error[0]) || std::isfinite(_error[1]), "EdgeVelocityObstacleRatio::computeError() _error[0]=%f , _error[1]=%f\n",_error[0],_error[1]);
123  }
124 
129  void setObstacle(const Obstacle* obstacle)
130  {
131  _measurement = obstacle;
132  }
133 
138  void setRobotModel(const BaseRobotFootprintModel* robot_model)
139  {
140  robot_model_ = robot_model;
141  }
142 
149  void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle)
150  {
151  cfg_ = &cfg;
152  robot_model_ = robot_model;
153  _measurement = obstacle;
154  }
155 
156 protected:
157 
159 
160 public:
161  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
162 
163 };
164 
165 
166 } // end namespace
double obstacle_proximity_lower_bound
Distance to a static obstacle for which the velocity should be lower.
Definition: teb_config.h:139
PoseSE2 & pose()
Access the pose.
Definition: vertex_pose.h:121
double penaltyBoundToInterval(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var to the interval .
Definition: penalties.h:57
Config class for the teb_local_planner and its components.
Definition: teb_config.h:61
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
Abstract class that defines the interface for robot footprint/contour models.
const BaseRobotFootprintModel * robot_model_
Store pointer to robot_model.
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
Edge defining the cost function for keeping a minimum distance from obstacles.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
double fast_sigmoid(double x)
Calculate a fast approximation of a sigmoid function.
Definition: misc.h:95
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: vertex_pose.h:173
Base edge connecting multiple vertices in the TEB optimization problem.
#define ROS_ASSERT_MSG(cond,...)
double max_vel_theta
Maximum angular velocity of the robot.
Definition: teb_config.h:99
void setRobotModel(const BaseRobotFootprintModel *robot_model)
Set pointer to the robot model.
bool exact_arc_length
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computation...
Definition: teb_config.h:82
Eigen::Vector2d & position()
Access the 2D position part.
Definition: vertex_pose.h:136
double obstacle_proximity_ratio_max_vel
Ratio of the maximum velocities used as an upper bound when reducing the speed due to the proximity t...
Definition: teb_config.h:138
const TebConfig * cfg_
Store TebConfig class for parameters.
double obstacle_proximity_upper_bound
Distance to a static obstacle for which the velocity should be higher.
Definition: teb_config.h:140
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)
void setObstacle(const Obstacle *obstacle)
Set pointer to associated obstacle for the underlying cost function.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
Abstract class that defines the interface for modelling obstacles.
Definition: obstacles.h:67
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:95
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const =0
Calculate the distance between the robot and an obstacle.
This class stores and wraps a time difference into a vertex that can be optimized via g2o...


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 1 2022 02:26:31