edge_dynamic_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, Franz Albers
42  *********************************************************************/
43 
44 #ifndef EDGE_DYNAMICOBSTACLE_H
45 #define EDGE_DYNAMICOBSTACLE_H
46 
54 
55 namespace teb_local_planner
56 {
57 
71 class EdgeDynamicObstacle : public BaseTebUnaryEdge<2, const Obstacle*, VertexPose>
72 {
73 public:
74 
78  EdgeDynamicObstacle() : t_(0)
79  {
80  }
81 
86  EdgeDynamicObstacle(double t) : t_(t)
87  {
88  }
89 
93  void computeError()
94  {
95  ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setObstacle() on EdgeDynamicObstacle()");
96  const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
97 
98  double dist = cfg_->robot_model->estimateSpatioTemporalDistance(bandpt->pose(), _measurement, t_);
99 
102 
103  ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeDynamicObstacle::computeError() _error[0]=%f\n",_error[0]);
104  }
105 
106 
111  void setObstacle(const Obstacle* obstacle)
112  {
113  _measurement = obstacle;
114  }
115 
121  void setParameters(const TebConfig& cfg, const Obstacle* obstacle)
122  {
123  cfg_ = &cfg;
124  _measurement = obstacle;
125  }
126 
127 protected:
128 
129  double t_;
130 
131 public:
132  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
133 
134 };
135 
136 
137 } // end namespace
138 
139 #endif
teb_local_planner::penaltyBoundFromBelow
double penaltyBoundFromBelow(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var from below: .
Definition: penalties.h:143
teb_local_planner::EdgeDynamicObstacle::setParameters
void setParameters(const TebConfig &cfg, const Obstacle *obstacle)
Set all parameters at once.
Definition: edge_dynamic_obstacle.h:162
teb_local_planner::TebConfig::Obstacles::dynamic_obstacle_inflation_dist
double dynamic_obstacle_inflation_dist
Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be la...
Definition: teb_config.h:131
teb_local_planner::TebConfig::Optimization::penalty_epsilon
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
Definition: teb_config.h:157
teb_local_planner::Obstacle
Abstract class that defines the interface for modelling obstacles.
Definition: obstacles.h:103
teb_local_planner::BaseTebUnaryEdge< 2, const Obstacle *, VertexPose >::cfg_
const TebConfig * cfg_
Store TebConfig class for parameters.
Definition: base_teb_edges.h:160
obstacles.h
teb_config.h
teb_local_planner::TebConfig::Obstacles::min_obstacle_dist
double min_obstacle_dist
Minimum desired separation from obstacles.
Definition: teb_config.h:129
penalties.h
robot_footprint_model.h
vertex_timediff.h
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
teb_local_planner::EdgeDynamicObstacle::setObstacle
void setObstacle(const Obstacle *obstacle)
Set Obstacle for the underlying cost function.
Definition: edge_dynamic_obstacle.h:152
teb_local_planner::EdgeDynamicObstacle::t_
double t_
Estimated time until current pose is reached.
Definition: edge_dynamic_obstacle.h:170
teb_local_planner::TebConfig
Config class for the teb_local_planner and its components.
Definition: teb_config.h:62
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
base_teb_edges.h
teb_local_planner::EdgeDynamicObstacle::computeError
void computeError()
Actual cost function.
Definition: edge_dynamic_obstacle.h:134
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::EdgeDynamicObstacle::EdgeDynamicObstacle
EdgeDynamicObstacle()
Construct edge.
Definition: edge_dynamic_obstacle.h:119
t
geometry_msgs::TransformStamped t
teb_local_planner::TebConfig::optim
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.


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