Go to the documentation of this file.
66 class EdgeVelocityObstacleRatio :
public BaseTebMultiEdge<2, const Obstacle*>
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]);
89 const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position();
91 double dist = deltaS.norm();
92 const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta());
95 double radius = dist/(2*sin(angle_diff/2));
96 dist = fabs( angle_diff * radius );
98 double vel = dist / deltaT->estimate();
100 vel *=
fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) );
102 const double omega = angle_diff / deltaT->estimate();
104 double dist_to_obstacle =
cfg_->
robot_model->calculateDistance(conf1->pose(), _measurement);
107 if (dist_to_obstacle < cfg_->obstacles.obstacle_proximity_lower_bound)
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]);
130 _measurement = obstacle;
138 void setParameters(
const TebConfig& cfg,
const Obstacle* obstacle)
141 _measurement = obstacle;
144 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool exact_arc_length
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computation...
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...
double penaltyBoundToInterval(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var to the interval .
EdgeVelocityObstacleRatio()
Construct edge.
Abstract class that defines the interface for modelling obstacles.
void setParameters(const TebConfig &cfg, const Obstacle *obstacle)
Set all parameters at once.
double fast_sigmoid(double x)
Calculate a fast approximation of a sigmoid function.
double obstacle_proximity_lower_bound
Distance to a static obstacle for which the velocity should be lower.
void setObstacle(const Obstacle *obstacle)
Set pointer to associated obstacle for the underlying cost function.
double obstacle_proximity_upper_bound
Distance to a static obstacle for which the velocity should be higher.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
#define ROS_ASSERT_MSG(cond,...)
void computeError()
Actual cost function.
const TebConfig * cfg_
Store TebConfig class for parameters.
double max_vel_x
Maximum translational velocity of the robot.
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
RobotFootprintModelPtr robot_model
model of the robot's footprint
virtual void resize(size_t size)
double max_vel_theta
Maximum angular velocity of the robot.
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15