43 #ifndef EDGE_OBSTACLE_H_ 44 #define EDGE_OBSTACLE_H_ 105 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeObstacle::computeError() _error[0]=%f\n",_error[0]);
108 #ifdef USE_ANALYTIC_JACOBI 114 void linearizeOplus()
119 Eigen::Vector2d deltaS = *_measurement - bandpt->
position();
120 double angdiff =
atan2(deltaS[1],deltaS[0])-bandpt->
theta();
122 double dist_squared = deltaS.squaredNorm();
123 double dist =
sqrt(dist_squared);
125 double aux0 =
sin(angdiff);
128 if (dev_left_border==0)
130 _jacobianOplusXi( 0 , 0 ) = 0;
131 _jacobianOplusXi( 0 , 1 ) = 0;
132 _jacobianOplusXi( 0 , 2 ) = 0;
136 double aux1 = -fabs(aux0) / dist;
137 double dev_norm_x = deltaS[0]*aux1;
138 double dev_norm_y = deltaS[1]*aux1;
141 double aux3 = aux2 / dist_squared;
142 double dev_proj_x = aux3 * deltaS[1] * dist;
143 double dev_proj_y = -aux3 * deltaS[0] * dist;
144 double dev_proj_angle = -aux2;
146 _jacobianOplusXi( 0 , 0 ) = dev_left_border * ( dev_norm_x + dev_proj_x );
147 _jacobianOplusXi( 0 , 1 ) = dev_left_border * ( dev_norm_y + dev_proj_y );
148 _jacobianOplusXi( 0 , 2 ) = dev_left_border * dev_proj_angle;
159 _measurement = obstacle;
181 _measurement = obstacle;
189 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
226 ROS_ASSERT_MSG(
cfg_ && _measurement &&
robot_model_,
"You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeInflatedObstacle()");
249 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]),
"EdgeInflatedObstacle::computeError() _error[0]=%f, _error[1]=%f\n",_error[0], _error[1]);
258 _measurement = obstacle;
280 _measurement = obstacle;
288 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
double penaltyBoundFromBelow(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var from below: .
EdgeInflatedObstacle()
Construct edge.
const BaseRobotFootprintModel * robot_model_
Store pointer to robot_model.
PoseSE2 & pose()
Access the pose.
void setRobotModel(const BaseRobotFootprintModel *robot_model)
Set pointer to the robot model.
double min_obstacle_dist
Minimum desired separation from obstacles.
Config class for the teb_local_planner and its components.
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.
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.
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.
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: .
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
Eigen::Vector2d & position()
Access the 2D position part.
double obstacle_cost_exponent
Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent). Set to 1 to disable nonlinear cost (default)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
EdgeObstacle()
Construct edge.
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
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 ...
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.