85 ROS_ASSERT_MSG(
cfg_ && _measurement &&
robot_model_,
"You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeVelocityObstacleRatio()");
90 const Eigen::Vector2d deltaS = conf2->estimate().
position() - conf1->estimate().
position();
92 double dist = deltaS.norm();
93 const double angle_diff = g2o::normalize_theta(conf2->
theta() - conf1->
theta());
96 double radius = dist/(2*
sin(angle_diff/2));
97 dist = fabs( angle_diff * radius );
99 double vel = dist / deltaT->estimate();
103 const double omega = angle_diff / deltaT->estimate();
108 if (dist_to_obstacle < cfg_->obstacles.obstacle_proximity_lower_bound)
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]);
131 _measurement = obstacle;
153 _measurement = obstacle;
161 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual void resize(size_t size)
double obstacle_proximity_lower_bound
Distance to a static obstacle for which the velocity should be lower.
PoseSE2 & pose()
Access the pose.
double penaltyBoundToInterval(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var to the interval .
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 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.
double & theta()
Access the orientation part (yaw angle) of the pose.
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.
EdgeVelocityObstacleRatio()
Construct edge.
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...
void computeError()
Actual cost function.
Eigen::Vector2d & position()
Access the 2D position part.
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...
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.
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)
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.
double max_vel_x
Maximum translational velocity of the robot.
This class stores and wraps a time difference into a vertex that can be optimized via g2o...