Bootstrap

TEB teb_local_planner 构建超图过程error cost分析

G2O 背景

G20 边和顶点的定义
https://blog.csdn.net/weixin_43013761/category_11647404.html
使用G20优化器 优化 路径
https://blog.csdn.net/qq_29598161/article/details/115414732
https://zhuanlan.zhihu.com/p/121628349

buildGraph

TebOptimalPlanner::buildGraph 位于 optimal_planner.cpp 文件内,是整个teb planner 的核心

1. 添加顶点 AddTEBVertices

主要是添加位姿顶点时间间隔顶点
顶点分姿态顶点和时间顶点
1.1.
姿态顶点 VertexPose 内部需要优化的变量主要有三个 x,y,theta
1.2
时间顶点 TimeDiffVertex 内部需要优化的变量主要有1个 dt

void TebOptimalPlanner::AddTEBVertices()
{
  // add vertices to graph
  ROS_DEBUG_COND(cfg_->optim.optimization_verbose, "Adding TEB vertices ...");
  unsigned int id_counter = 0; // used for vertices ids
  for (int i=0; i<teb_.sizePoses(); ++i)
  {
    //基本状态 x,y,theta
    teb_.PoseVertex(i)->setId(id_counter++);//先赋值 再自行+1
    optimizer_->addVertex(teb_.PoseVertex(i));
    if (teb_.sizeTimeDiffs()!=0 && i<teb_.sizeTimeDiffs())
    {
      //基本状态 dt
      teb_.TimeDiffVertex(i)->setId(id_counter++);//先赋值 再自行+1 id 累积增加
      optimizer_->addVertex(teb_.TimeDiffVertex(i));
    }
  } 
}

2 Edge 的边的定义与Cost误差函数定义

使用到的惩罚函数
double penaltyBoundFromBelow(const double& var, const double& a,const double& epsilon)
函数定义如下
f ( x ) = { 0.0 , if  v a r > = a + e p s i l o n − v a r + ( a + e p s i l o n ) , if  v a r < ( a + e p s i l o n ) f(x) = \begin{cases} 0.0, & \text{if } var >= a+epsilon \\ -var + (a + epsilon), & \text{if } var < (a+epsilon) \\ \end{cases} f(x)={0.0,var+(a+epsilon),if var>=a+epsilonif var<(a+epsilon)

2.1 EdgeObstacle

误差函数计算代码

  void computeError()
  {
    获取顶点姿态
    const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);

    double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement);

    // Original obstacle cost.
    _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon);

    if (cfg_->optim.obstacle_cost_exponent != 1.0 && cfg_->obstacles.min_obstacle_dist > 0.0)
    {
      // Optional non-linear cost. 
      _error[0] = cfg_->obstacles.min_obstacle_dist * std::pow(_error[0] / cfg_->obstacles.min_obstacle_dist, cfg_->optim.obstacle_cost_exponent);
    }

    ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeObstacle::computeError() _error[0]=%f\n",_error[0]);
  }

如果配置文件 obstacle_cost_exponent == 1.0 那么error为线性函数公式整理如下
e r r o r [ 0 ] = { 0.0 , if  d i s t > = o b s . m i n _ d i s t + o p t i m . p e n a l t y _ e p s i l o n − d i s t + ( o b s . m i n _ d i s t + o p t i m . p e n a l t y _ e p s i l o n ) , else  error[0] = \begin{cases} 0.0, & \text{if } dist >= obs.min\_dist+optim.penalty\_epsilon \\ -dist + (obs.min\_dist+optim.penalty\_epsilon), & \text{else }\\ \end{cases} error[0]={0.0,dist+(obs.min_dist+optim.penalty_epsilon),if dist>=obs.min_dist+optim.penalty_epsilonelse 
如果配置文件 obstacle_cost_exponent != 1.0 那么error[0]继续更新为非线性函数公式整理如下
e r r o r [ 0 ] = o b s . m i n _ d i s t ∗ e r r o r [ 0 ] o b s . m i n _ d i s t c o s t _ e x p o e n t error[0] = obs.min\_dist * \frac{error[0] }{obs.min\_dist}^{cost\_expoent} error[0]=obs.min_distobs.min_disterror[0]cost_expoent

2.2 EdgeInflatedObstacle

  • EdgeInflatedObstacle 是一个一元边 继承于 public BaseTebUnaryEdge<2, const Obstacle*, VertexPose>
  • 观测类型是const Obstacle*
  • 连接的顶点是VertexPose
  void computeError()
  {
    const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
    double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement);
    _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon);
    if (cfg_->optim.obstacle_cost_exponent != 1.0 && cfg_->obstacles.min_obstacle_dist > 0.0)
    {
      // Optional non-linear cost. 
      _error[0] = cfg_->obstacles.min_obstacle_dist * std::pow(_error[0] / cfg_->obstacles.min_obstacle_dist, cfg_->optim.obstacle_cost_exponent);
    }
    // Additional linear inflation cost
    _error[1] = penaltyBoundFromBelow(dist, cfg_->obstacles.inflation_dist, 0.0);
  }

error[0]的计算和EdgeObstacle 类型一样,额外增加一个error[1]
e r r o r [ 1 ] = { 0.0 , if  d i s t > = o b s . i n f l a t i o n _ d i s t − d i s t + ( o b s . i n f l a t i o n _ d i s t ) , else  error[1] = \begin{cases} 0.0, & \text{if } dist >= obs.inflation\_dist \\ -dist + (obs.inflation\_dist), & \text{else }\\ \end{cases} error[1]={0.0,dist+(obs.inflation_dist),if dist>=obs.inflation_distelse 

2.3 EdgeDynamicObstacle

  • EdgeDynamicObstacle 继承于 BaseTebUnaryEdge<2, const Obstacle*, VertexPose> 是一个一元边
  void computeError()
  {
    const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
    double dist = robot_model_->estimateSpatioTemporalDistance(bandpt->pose(), _measurement, t_);
    _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon);
    _error[1] = penaltyBoundFromBelow(dist, cfg_->obstacles.dynamic_obstacle_inflation_dist, 0.0);
  }
  • 该函数dist主要是预测障碍物在t秒后的位置和姿态顶点的距离
    robot_model_->estimateSpatioTemporalDistance
  • error[0] 计算和EdgeInflatedObstacle EdgeObstacle相同
  • error[1] 主要使用dynamic_obstacle_inflation_dist来判断

2.4 EdgeViaPoint

  • class EdgeViaPoint 继承 BaseTebUnaryEdge<1, const Eigen::Vector2d*, VertexPose> 一元边
  • 误差向量维度1
  • 观测为Eigen::Vector2d*
  void computeError()
  {
    const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
    _error[0] = (bandpt->position() - *_measurement).norm();
  }

总结

  • EdgeViaPoint 主要是评判机器人贴合原始路径的error cost 离原始点位越远 则 error cost 越大

2.5 EdgeVelocity

  • EdgeVelocity 继承 public BaseTebMultiEdge<2, double> 三元边
  • 连接了3个顶点 2个姿态顶点 1个时间顶点
  void computeError()
  {
    const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
    const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
    const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
    
    const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position();
    
    double dist = deltaS.norm();
    const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta());
    if (cfg_->trajectory.exact_arc_length && angle_diff != 0)
    {
        double radius =  dist/(2*sin(angle_diff/2));
        dist = fabs( angle_diff * radius ); // actual arg length!
    }
    double vel = dist / deltaT->estimate();
    
//     vel *= g2o::sign(deltaS[0]*cos(conf1->theta()) + deltaS[1]*sin(conf1->theta())); // consider direction
    vel *= fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) ); // consider direction
    
    const double omega = angle_diff / deltaT->estimate();
  
    _error[0] = penaltyBoundToInterval(vel, -cfg_->robot.max_vel_x_backwards, cfg_->robot.max_vel_x,cfg_->optim.penalty_epsilon);
    _error[1] = penaltyBoundToInterval(omega, cfg_->robot.max_vel_theta,cfg_->optim.penalty_epsilon);
  }

penaltyBoundToInterval 函数如下

inline double penaltyBoundToInterval(const double& var,const double& a, const double& b, const double& epsilon)
{
  if (var < a+epsilon)
  {
    return (-var + (a + epsilon));
  }
  if (var <= b-epsilon)
  {
    return 0.;
  }
  else
  {
    return (var - (b - epsilon));
  }
}

总结

  • EdgeVelocity 主要是控制了路径的最大最小速度进行的error cost评判 使得机器人速度 以及角速度在合理的范围之内

2.6 EdgeAcceleration

  • class EdgeAcceleration 继承 public BaseTebMultiEdge<2, double> 多元边
  void computeError()
  {
    ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()");
    const VertexPose* pose1 = static_cast<const VertexPose*>(_vertices[0]);
    const VertexPose* pose2 = static_cast<const VertexPose*>(_vertices[1]);
    const VertexPose* pose3 = static_cast<const VertexPose*>(_vertices[2]);
    const VertexTimeDiff* dt1 = static_cast<const VertexTimeDiff*>(_vertices[3]);
    const VertexTimeDiff* dt2 = static_cast<const VertexTimeDiff*>(_vertices[4]);

    // VELOCITY & ACCELERATION
    const Eigen::Vector2d diff1 = pose2->position() - pose1->position();
    const Eigen::Vector2d diff2 = pose3->position() - pose2->position();
        
    double dist1 = diff1.norm();
    double dist2 = diff2.norm();
    const double angle_diff1 = g2o::normalize_theta(pose2->theta() - pose1->theta());
    const double angle_diff2 = g2o::normalize_theta(pose3->theta() - pose2->theta());
    
    if (cfg_->trajectory.exact_arc_length) // use exact arc length instead of Euclidean approximation
    {
        if (angle_diff1 != 0)
        {
            const double radius =  dist1/(2*sin(angle_diff1/2));
            dist1 = fabs( angle_diff1 * radius ); // actual arg length!
        }
        if (angle_diff2 != 0)
        {
            const double radius =  dist2/(2*sin(angle_diff2/2));
            dist2 = fabs( angle_diff2 * radius ); // actual arg length!
        }
    }
    
    double vel1 = dist1 / dt1->dt();
    double vel2 = dist2 / dt2->dt();
    
    
    // consider directions
//     vel1 *= g2o::sign(diff1[0]*cos(pose1->theta()) + diff1[1]*sin(pose1->theta())); 
//     vel2 *= g2o::sign(diff2[0]*cos(pose2->theta()) + diff2[1]*sin(pose2->theta())); 
    vel1 *= fast_sigmoid( 100*(diff1.x()*cos(pose1->theta()) + diff1.y()*sin(pose1->theta())) ); 
    vel2 *= fast_sigmoid( 100*(diff2.x()*cos(pose2->theta()) + diff2.y()*sin(pose2->theta())) ); 
    
    const double acc_lin  = (vel2 - vel1)*2 / ( dt1->dt() + dt2->dt() );
   

    _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon);
    
    // ANGULAR ACCELERATION
    const double omega1 = angle_diff1 / dt1->dt();
    const double omega2 = angle_diff2 / dt2->dt();
    const double acc_rot  = (omega2 - omega1)*2 / ( dt1->dt() + dt2->dt() );
      
    _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon);

    
    ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAcceleration::computeError() translational: _error[0]=%f\n",_error[0]);
    ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAcceleration::computeError() rotational: _error[1]=%f\n",_error[1]);
  }

总结

  • 主要限制了最大角速度和角加速度

2.7 EdgeTimeOptimal

  • EdgeTimeOptimal 继承 public BaseTebUnaryEdge<1, double, VertexTimeDiff> 一元边
  • 误差向量维度为1
  void computeError()
  {
    const VertexTimeDiff* timediff = static_cast<const VertexTimeDiff*>(_vertices[0]);
   _error[0] = timediff->dt();
  }

总结

  • 时间越小越好, 这样子机器人会向最大速度去调整

2.8 EdgeShortestPath

  • EdgeShortestPath : public BaseTebBinaryEdge<1, double, VertexPose, VertexPose> 二元边
  • 误差向量维度为1
  void computeError() {
    const VertexPose *pose1 = static_cast<const VertexPose*>(_vertices[0]);
    const VertexPose *pose2 = static_cast<const VertexPose*>(_vertices[1]);
    _error[0] = (pose2->position() - pose1->position()).norm();
  }

总结

  • 两个姿态顶点之间的距离越小cost 越低

2.9 EdgeKinematicsDiffDrive

  • EdgeKinematicsDiffDrive : public BaseTebBinaryEdge<2, double, VertexPose, VertexPose> 二元边
  • 误差维度为2
    nage
  void computeError()
  {
    const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
    const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
    
    Eigen::Vector2d deltaS = conf2->position() - conf1->position();

    // non holonomic constraint
    _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );

    // positive-drive-direction constraint
    Eigen::Vector2d angle_vec ( cos(conf1->theta()), sin(conf1->theta()) );	   
    _error[1] = penaltyBoundFromBelow(deltaS.dot(angle_vec), 0,0);
    // epsilon=0, otherwise it pushes the first bandpoints away from start
  }

总结

  • 不允许反方向
  • 不允许 超越动力学范围

2.10 EdgePreferRotDir

  • EdgePreferRotDir : public BaseTebBinaryEdge<1, double, VertexPose, VertexPose> 二元边
  • 误差维度为1
  void computeError()
  {
    const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
    const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);    
    _error[0] = penaltyBoundFromBelow( _measurement*g2o::normalize_theta(conf2->theta()-conf1->theta()) , 0, 0);
  }

总结

  • 主要是前3个姿态点 更偏向偏向朝哪个个方向旋转
;