Go to the documentation of this file.
44 #ifndef EDGE_DYNAMICOBSTACLE_H
45 #define EDGE_DYNAMICOBSTACLE_H
71 class EdgeDynamicObstacle :
public BaseTebUnaryEdge<2, const Obstacle*, VertexPose>
95 ROS_ASSERT_MSG(
cfg_ && _measurement,
"You must call setTebConfig() and setObstacle() on EdgeDynamicObstacle()");
96 const VertexPose* bandpt =
static_cast<const VertexPose*
>(_vertices[0]);
98 double dist =
cfg_->
robot_model->estimateSpatioTemporalDistance(bandpt->pose(), _measurement,
t_);
103 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeDynamicObstacle::computeError() _error[0]=%f\n",_error[0]);
113 _measurement = obstacle;
124 _measurement = obstacle;
132 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
double penaltyBoundFromBelow(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var from below: .
void setParameters(const TebConfig &cfg, const Obstacle *obstacle)
Set all parameters at once.
double dynamic_obstacle_inflation_dist
Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be la...
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
Abstract class that defines the interface for modelling obstacles.
const TebConfig * cfg_
Store TebConfig class for parameters.
double min_obstacle_dist
Minimum desired separation from obstacles.
#define ROS_ASSERT_MSG(cond,...)
void setObstacle(const Obstacle *obstacle)
Set Obstacle for the underlying cost function.
double t_
Estimated time until current pose is reached.
Config class for the teb_local_planner and its components.
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
RobotFootprintModelPtr robot_model
model of the robot's footprint
void computeError()
Actual cost function.
EdgeDynamicObstacle()
Construct edge.
geometry_msgs::TransformStamped t
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