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  {
75  // The three vertices are two poses and one time difference
76  this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices
77  }
78 
82  void computeError()
83  {
84  ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setObstacle() on EdgeVelocityObstacleRatio()");
85  const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
86  const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
87  const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
88 
89  const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position();
90 
91  double dist = deltaS.norm();
92  const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta());
93  if (cfg_->trajectory.exact_arc_length && angle_diff != 0)
94  {
95  double radius = dist/(2*sin(angle_diff/2));
96  dist = fabs( angle_diff * radius ); // actual arg length!
97  }
98  double vel = dist / deltaT->estimate();
99 
100  vel *= fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) ); // consider direction
101 
102  const double omega = angle_diff / deltaT->estimate();
103 
104  double dist_to_obstacle = cfg_->robot_model->calculateDistance(conf1->pose(), _measurement);
105 
106  double ratio;
107  if (dist_to_obstacle < cfg_->obstacles.obstacle_proximity_lower_bound)
108  ratio = 0;
109  else if (dist_to_obstacle > cfg_->obstacles.obstacle_proximity_upper_bound)
110  ratio = 1;
111  else
112  ratio = (dist_to_obstacle - cfg_->obstacles.obstacle_proximity_lower_bound) /
115 
116  const double max_vel_fwd = ratio * cfg_->robot.max_vel_x;
117  const double max_omega = ratio * cfg_->robot.max_vel_theta;
118  _error[0] = penaltyBoundToInterval(vel, max_vel_fwd, 0);
119  _error[1] = penaltyBoundToInterval(omega, max_omega, 0);
120 
121  ROS_ASSERT_MSG(std::isfinite(_error[0]) || std::isfinite(_error[1]), "EdgeVelocityObstacleRatio::computeError() _error[0]=%f , _error[1]=%f\n",_error[0],_error[1]);
122  }
123 
128  void setObstacle(const Obstacle* obstacle)
129  {
130  _measurement = obstacle;
131  }
132 
138  void setParameters(const TebConfig& cfg, const Obstacle* obstacle)
139  {
140  cfg_ = &cfg;
141  _measurement = obstacle;
142  }
143 
144  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
145 
146 };
147 
148 } // end namespace
teb_local_planner::TebConfig::Trajectory::exact_arc_length
bool exact_arc_length
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computation...
Definition: teb_config.h:85
teb_local_planner::TebConfig::Obstacles::obstacle_proximity_ratio_max_vel
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:142
teb_local_planner::penaltyBoundToInterval
double penaltyBoundToInterval(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var to the interval .
Definition: penalties.h:93
teb_local_planner::EdgeVelocityObstacleRatio::EdgeVelocityObstacleRatio
EdgeVelocityObstacleRatio()
Construct edge.
Definition: edge_velocity_obstacle_ratio.h:113
teb_local_planner::Obstacle
Abstract class that defines the interface for modelling obstacles.
Definition: obstacles.h:103
teb_local_planner::EdgeVelocityObstacleRatio::setParameters
void setParameters(const TebConfig &cfg, const Obstacle *obstacle)
Set all parameters at once.
Definition: edge_velocity_obstacle_ratio.h:178
teb_local_planner::fast_sigmoid
double fast_sigmoid(double x)
Calculate a fast approximation of a sigmoid function.
Definition: misc.h:131
teb_local_planner::TebConfig::Obstacles::obstacle_proximity_lower_bound
double obstacle_proximity_lower_bound
Distance to a static obstacle for which the velocity should be lower.
Definition: teb_config.h:143
teb_local_planner::EdgeVelocityObstacleRatio::setObstacle
void setObstacle(const Obstacle *obstacle)
Set pointer to associated obstacle for the underlying cost function.
Definition: edge_velocity_obstacle_ratio.h:168
teb_local_planner::TebConfig::Obstacles::obstacle_proximity_upper_bound
double obstacle_proximity_upper_bound
Distance to a static obstacle for which the velocity should be higher.
Definition: teb_config.h:144
teb_local_planner::TebConfig::trajectory
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
robot_footprint_model.h
teb_local_planner::TebConfig::robot
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
vertex_timediff.h
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
teb_local_planner::EdgeVelocityObstacleRatio::computeError
void computeError()
Actual cost function.
Definition: edge_velocity_obstacle_ratio.h:122
teb_local_planner::BaseTebMultiEdge< 2, const Obstacle * >::cfg_
const TebConfig * cfg_
Store TebConfig class for parameters.
Definition: base_teb_edges.h:306
teb_local_planner::TebConfig::Robot::max_vel_x
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:99
teb_local_planner::TebConfig::obstacles
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
vertex_pose.h
teb_local_planner::TebConfig::robot_model
RobotFootprintModelPtr robot_model
model of the robot's footprint
Definition: teb_config.h:69
teb_local_planner::BaseTebMultiEdge< 2, const Obstacle * >::resize
virtual void resize(size_t size)
Definition: base_teb_edges.h:254
base_teb_edges.h
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::TebConfig::Robot::max_vel_theta
double max_vel_theta
Maximum angular velocity of the robot.
Definition: teb_config.h:103


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15