TEB局部路径规划算法代码及原理解读

news2024/11/16 19:01:05

TEB(Timed Elastic Band) 是一个基于图优化的局部路径规划算法,具有较好的动态避障能力,在ROS1/ROS2的导航框架中均被采用。该图优化以g2o优化框架实现,以机器人在各个离散时刻的位姿和离散时刻之间的时间间隔为顶点,约束其中的加速度、速度,到达时间和到障碍物的距离等值,优化目标是使得机器人在其运动学约束下绕开障碍物最快到达目标点,实现了高效的局部路径规划功能。整个算法流程如下,其中的重点是图结构的构建。
TEB Github

TEB

一,加入顶点
顶点包括:离散时刻机器人位姿和离散时间间隔。

void TebOptimalPlanner::AddTEBVertices()
{
  // add vertices to graph
  RCLCPP_DEBUG_EXPRESSION(node_->get_logger(), cfg_->optim.optimization_verbose, "Adding TEB vertices ...");
  unsigned int id_counter = 0; // used for vertices ids
  obstacles_per_vertex_.resize(teb_.sizePoses());
  auto iter_obstacle = obstacles_per_vertex_.begin();
  for (int i=0; i<teb_.sizePoses(); ++i)
  {
    teb_.PoseVertex(i)->setId(id_counter++);
    optimizer_->addVertex(teb_.PoseVertex(i));
    if (teb_.sizeTimeDiffs()!=0 && i<teb_.sizeTimeDiffs())
    {
      teb_.TimeDiffVertex(i)->setId(id_counter++);
      optimizer_->addVertex(teb_.TimeDiffVertex(i));
    }
    iter_obstacle->clear();
    (iter_obstacle++)->reserve(obstacles_->size());
  }
}

二,构建边

bool TebOptimalPlanner::buildGraph(double weight_multiplier)
{
  if (!optimizer_->edges().empty() || !optimizer_->vertices().empty())
  {
    RCLCPP_WARN(node_->get_logger(), "Cannot build graph, because it is not empty. Call graphClear()!");
    return false;
  }

  optimizer_->setComputeBatchStatistics(cfg_->recovery.divergence_detection_enable);
  
  // add TEB vertices
  AddTEBVertices();
  
  // add Edges (local cost functions)
  // 增加与静态障碍物相关的边
  if (cfg_->obstacles.legacy_obstacle_association)
    AddEdgesObstaclesLegacy(weight_multiplier);
  else
    AddEdgesObstacles(weight_multiplier);
  
  // 增加与动态障碍物有关的边
  if (cfg_->obstacles.include_dynamic_obstacles)
    AddEdgesDynamicObstacles();
  // 增加约束到中间点的边,只关注目标点时,可以不增加这类边
  AddEdgesViaPoints();
  // 增加速度约束边  
  AddEdgesVelocity();
  // 增加加速度约束边
  AddEdgesAcceleration();
  // 增加总耗时约束边
  AddEdgesTimeOptimal();	
  // 增加最短路径边, 可不增加
  AddEdgesShortestPath();
  // 针对差速底盘和阿克曼底盘的运动学约束边
  if (cfg_->robot.min_turning_radius == 0 || cfg_->optim.weight_kinematics_turning_radius == 0)
    AddEdgesKinematicsDiffDrive(); // we have a differential drive robot
  else
    AddEdgesKinematicsCarlike(); // we have a carlike robot since the turning radius is bounded from below.
  // 增加偏好转向的边, 可不增加
  AddEdgesPreferRotDir();
  // 增加接近障碍物时速度约束边
  if (cfg_->optim.weight_velocity_obstacle_ratio > 0)
    AddEdgesVelocityObstacleRatio();
    
  return true;  
}

图优化涉及到多种约束边时,各自的权重很重要,代码中对各个权重做了注释,也能很好地看出各个约束边的作用。


    double weight_max_vel_x; //!< Optimization weight for satisfying the maximum allowed translational velocity
    double weight_max_vel_y; //!< Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots)
    double weight_max_vel_theta; //!< Optimization weight for satisfying the maximum allowed angular velocity
    double weight_acc_lim_x; //!< Optimization weight for satisfying the maximum allowed translational acceleration
    double weight_acc_lim_y; //!< Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots)
    double weight_acc_lim_theta; //!< Optimization weight for satisfying the maximum allowed angular acceleration
    double weight_kinematics_nh; //!< Optimization weight for satisfying the non-holonomic kinematics
    double weight_kinematics_forward_drive; //!< Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot)
    double weight_kinematics_turning_radius; //!< Optimization weight for enforcing a minimum turning radius (carlike robots)
    double weight_optimaltime; //!< Optimization weight for contracting the trajectory w.r.t. transition time
    double weight_shortest_path; //!< Optimization weight for contracting the trajectory w.r.t. path length
    double weight_obstacle; //!< Optimization weight for satisfying a minimum separation from obstacles
    double weight_inflation; //!< Optimization weight for the inflation penalty (should be small)
    double weight_dynamic_obstacle; //!< Optimization weight for satisfying a minimum separation from dynamic obstacles
    double weight_dynamic_obstacle_inflation; //!< Optimization weight for the inflation penalty of dynamic obstacles (should be small)
    double weight_velocity_obstacle_ratio; //!< Optimization weight for satisfying a maximum allowed velocity with respect to the distance to a static obstacle
    double weight_viapoint; //!< Optimization weight for minimizing the distance to via-points
    double weight_prefer_rotdir; //!< Optimization weight for preferring a specific turning direction (-> currently only activated if an oscillation is detected, see 'oscillation_recovery'

    double weight_adapt_factor; //!< Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer TEB iteration (weight_new = weight_old*factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem.
    double obstacle_cost_exponent; //!< Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent). Set to 1 to disable nonlinear cost (default)

三,避障相关约束
TEB通过让位姿远离障碍物来达到避障的目的,并将障碍物分为动态障碍物和静态障碍物处理。

if (cfg_->obstacles.legacy_obstacle_association)
    AddEdgesObstaclesLegacy(weight_multiplier);
  else
    AddEdgesObstacles(weight_multiplier);

  if (cfg_->obstacles.include_dynamic_obstacles)
    AddEdgesDynamicObstacles();

参数Legacy_obstacle_association:
True: 对于每个障碍物,找到最近的TEB位姿,使其距离大于设定距离;
False: 对于每个TEB位姿,找到相关的障碍物,使其距离大于设定距离。

void TebOptimalPlanner::AddEdgesObstaclesLegacy(double weight_multiplier)
{
  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr)
    return; // weight_multiplier 被固定设为1.0
  Eigen::Matrix<double,1,1> information; 
  information.fill(cfg_->optim.weight_obstacle * weight_multiplier);
  Eigen::Matrix<double,2,2> information_inflated;
  information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier;
  information_inflated(1,1) = cfg_->optim.weight_inflation;
  information_inflated(0,1) = information_inflated(1,0) = 0;
  bool inflated = cfg_->obstacles.inflation_dist > cfg_->obstacles.min_obstacle_dist;
  // 如果障碍物膨胀距离大于距离障碍物的最小距离,才会考虑膨胀
  for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
  {
    if (cfg_->obstacles.include_dynamic_obstacles && (*obst)->isDynamic()) // we handle dynamic obstacles differently below
      continue;     
    int index;    
    if (cfg_->obstacles.obstacle_poses_affected >= teb_.sizePoses())
      index =  teb_.sizePoses() / 2;
    else
      index = teb_.findClosestTrajectoryPose(*(obst->get()));
     //对于每个障碍物,找到最近的TEB位姿    
    // check if obstacle is outside index-range between start and goal
    if ( (index <= 1) || (index > teb_.sizePoses()-2) ) // start and goal are fixed and findNearestBandpoint finds first or last conf if intersection point is outside the range
      continue;         
    if (inflated)
{  //考虑障碍物膨胀
   // 这种情况下,首先会使得障碍物与位姿距离大于设定的最小距离,其次距离在膨胀半径范围内是越大越好,距离超过膨胀半径,则残差为0
        EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
        dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
        dist_bandpt_obst->setInformation(information_inflated);
        dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get());
        optimizer_->addEdge(dist_bandpt_obst);
    }
    else
    {  // 不考虑障碍物膨胀,仅使得位姿距离障碍物大于设定的最小距离,距离大于该最小距离,则残差为0
        EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
        dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
        dist_bandpt_obst->setInformation(information);
        dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get());
        optimizer_->addEdge(dist_bandpt_obst);
    }
// 考虑障碍物对最近TEB位姿附近的位姿的影响 
    for (int neighbourIdx=0; neighbourIdx < floor(cfg_->obstacles.obstacle_poses_affected/2); neighbourIdx++)
    {
      if (index+neighbourIdx < teb_.sizePoses())
      {
            if (inflated)
            {
                EdgeInflatedObstacle* dist_bandpt_obst_n_r = new EdgeInflatedObstacle;
                dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
                dist_bandpt_obst_n_r->setInformation(information_inflated);
                dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get());
                optimizer_->addEdge(dist_bandpt_obst_n_r);
            }
            else
            {
                EdgeObstacle* dist_bandpt_obst_n_r = new EdgeObstacle;
                dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
                dist_bandpt_obst_n_r->setInformation(information);
                dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get());
                optimizer_->addEdge(dist_bandpt_obst_n_r);
            }
      }
      if ( index - neighbourIdx >= 0) // needs to be casted to int to allow negative values
      {
            if (inflated)
            {
                EdgeInflatedObstacle* dist_bandpt_obst_n_l = new EdgeInflatedObstacle;
                dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
                dist_bandpt_obst_n_l->setInformation(information_inflated);
                dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get());
                optimizer_->addEdge(dist_bandpt_obst_n_l);
            }
            else
            {
                EdgeObstacle* dist_bandpt_obst_n_l = new EdgeObstacle;
                dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
                dist_bandpt_obst_n_l->setInformation(information);
                dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get());
                optimizer_->addEdge(dist_bandpt_obst_n_l);
            }
      }
    }     
  }
}

void TebOptimalPlanner::AddEdgesObstacles(double weight_multiplier)
{
  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr )
    return; // if weight equals zero skip adding edges!
  bool inflated = cfg_->obstacles.inflation_dist > cfg_->obstacles.min_obstacle_dist;
  Eigen::Matrix<double,1,1> information;
  information.fill(cfg_->optim.weight_obstacle * weight_multiplier);
  Eigen::Matrix<double,2,2> information_inflated;
  information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier;
  information_inflated(1,1) = cfg_->optim.weight_inflation;
  information_inflated(0,1) = information_inflated(1,0) = 0;
  auto iter_obstacle = obstacles_per_vertex_.begin();
  auto create_edge = [inflated, &information, &information_inflated, this] (int index, const Obstacle* obstacle) {
    if (inflated)
    {
      EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
      dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
      dist_bandpt_obst->setInformation(information_inflated);
      dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obstacle);
      optimizer_->addEdge(dist_bandpt_obst);
    }
    else
    {
      EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
      dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
      dist_bandpt_obst->setInformation(information);
      dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obstacle);
      optimizer_->addEdge(dist_bandpt_obst);
    };
  };    
  // iterate all teb points, skipping the last and, if the EdgeVelocityObstacleRatio edges should not be created, the first one too
  const int first_vertex = cfg_->optim.weight_velocity_obstacle_ratio == 0 ? 1 : 0;
  for (int i = first_vertex; i < teb_.sizePoses() - 1; ++i)
  {    // 对于每一个TEB位姿,找到有影响的障碍物,并施加约束
      double left_min_dist = std::numeric_limits<double>::max();
      double right_min_dist = std::numeric_limits<double>::max();
      ObstaclePtr left_obstacle;
      ObstaclePtr right_obstacle;      
      const Eigen::Vector2d pose_orient = teb_.Pose(i).orientationUnitVec();
      // iterate obstacles
      for (const ObstaclePtr& obst : *obstacles_)
      {
        // we handle dynamic obstacles differently below
        if(cfg_->obstacles.include_dynamic_obstacles && obst->isDynamic())
          continue;
          // calculate distance to robot model
          double dist = robot_model_->calculateDistance(teb_.Pose(i), obst.get());
          // force considering obstacle if really close to the current pose
        if (dist < cfg_->obstacles.min_obstacle_dist*cfg_->obstacles.obstacle_association_force_inclusion_factor)
          {
              iter_obstacle->push_back(obst);
              continue;
          }
          // cut-off distance
          if (dist > cfg_->obstacles.min_obstacle_dist*cfg_->obstacles.obstacle_association_cutoff_factor)
            continue;          
          // determine side (left or right) and assign obstacle if closer than the previous one
          if (cross2d(pose_orient, obst->getCentroid()) > 0) // left
          {
              if (dist < left_min_dist)
              {
                  left_min_dist = dist;
                  left_obstacle = obst;
              }
          }
          else
          {
              if (dist < right_min_dist)
              {
                  right_min_dist = dist;
                  right_obstacle = obst;
              }
          }
      }         
      if (left_obstacle)
        iter_obstacle->push_back(left_obstacle);
      if (right_obstacle)
        iter_obstacle->push_back(right_obstacle);

      // continue here to ignore obstacles for the first pose, but use them later to create the EdgeVelocityObstacleRatio edges
      if (i == 0)
      {
        ++iter_obstacle;
        continue;
      }
      // create obstacle edges
      for (const ObstaclePtr obst : *iter_obstacle)
        create_edge(i, obst.get());
      ++iter_obstacle;
  }
}

涉及的参数
min_obstacle_dist: 机器人距离障碍物的最小距离,已经考虑了机器人的footprint形状;
inflation_dist: 膨胀距离,已经考虑了机器人的footprint形状;
obstacle_association_cutoff_factor: 在AddEdgesObstacles中,如果障碍物距离TEB位姿大于min_obstacle_dist* obstacle_association_cutoff_factor 则不会被考虑;
obstacle_association_force_inclusion_factor: 在AddEdgesObstacles中,如果障碍物距离TEB位姿小于min_obstacle_dist* obstacle_association_force_inclusion_factor 则会被考虑;
介于上述两者之间的,则只考虑左右方向最近的障碍物。

动态障碍物处理
对于每一个动态障碍物,所有TEB位姿都会被考虑进去,与静态障碍物的处理不同之处在于,会根据障碍物的速度和时间对未来其位置进行预测,以达到动态避障的目的。如果环境是低动态,可以将include_dynamic_obstacles设为False,及可不考虑动态障碍物。

void TebOptimalPlanner::AddEdgesDynamicObstacles(double weight_multiplier)
{
  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==NULL )
    return; // if weight equals zero skip adding edges!
  Eigen::Matrix<double,2,2> information;
  information(0,0) = cfg_->optim.weight_dynamic_obstacle * weight_multiplier;
  information(1,1) = cfg_->optim.weight_dynamic_obstacle_inflation;
  information(0,1) = information(1,0) = 0;
  for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
  {
    if (!(*obst)->isDynamic())
      continue;
    // Skip first and last pose, as they are fixed
    double time = teb_.TimeDiff(0);
    for (int i=1; i < teb_.sizePoses() - 1; ++i)
    {
      EdgeDynamicObstacle* dynobst_edge = new EdgeDynamicObstacle(time);
      dynobst_edge->setVertex(0,teb_.PoseVertex(i));
      dynobst_edge->setInformation(information);
      dynobst_edge->setParameters(*cfg_, robot_model_.get(), obst->get());
      optimizer_->addEdge(dynobst_edge);
      time += teb_.TimeDiff(i); // we do not need to check the time diff bounds, since we iterate to "< sizePoses()-1".
    }
  }
}

障碍物的来源

  1. 直接来自代价地图,包括静态层和障碍物层的障碍物
void TebLocalPlannerROS::updateObstacleContainerWithCostmap()
  1. 来自costmap_converter,最终来源与costmap一致
void TebLocalPlannerROS::updateObstacleContainerWithCostmapConverter()
  1. 来自收到的障碍物消息
void TebLocalPlannerROS::updateObstacleContainerWithCustomObstacles()

四,优缺点
优点:可自定义多种约束,动态避障效果较好,可跟随各种路径;
缺点:算力较大,在低算力嵌入式板子上很难跑起来,调参需要经验。

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/1924284.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

IEEE(常用)参考文献引用格式详解 | LaTeX参考文献规范(IEEE Trans、Conf、Arxiv)

IEEE参考文献引用格式注意事项 期刊已正式出版&#xff08;有期卷号&#xff09;录用后在线访问即Early access&#xff08;无期卷号&#xff09; Arxiv论文会议论文IEEE缩写进阶其他 IEEE论文投稿前的参考文献格式检查&#xff01;&#xff08;如果一些细节你采用别的形式&…

UE4 解决创建布料报错:三角形退化

**【问题】**创建创建布料时报错&#xff1a;三角形退化 【方法】 1.要重新绑定&#xff1a;导入到ue4为静态网格体&#xff0c;勾选“移除退化”&#xff0c;再导出fbx&#xff0c;再重新绑定 2.不用重新绑定&#xff1a;使用排除法&#xff08;费时&#xff09;&#xff0c…

开放式耳机选哪个牌子好?五大主流王炸爆款推荐!

在快节奏的现代生活中&#xff0c;音乐是不可或缺的慰藉。作为音乐迷&#xff0c;我追求音质卓越与佩戴舒适的耳机。开放式蓝牙耳机&#xff0c;以革新设计和技术&#xff0c;颠覆传统认知&#xff0c;既呈现高品质音乐盛宴&#xff0c;又确保长久佩戴的极致舒适&#xff0c;成…

记一次,由于发布配置引发的alpine中运行sqlite3的错误解决历程思路!

使用net的都知道&#xff0c;打包镜像的时候的基础包有2个选择(实际上更多) 比如我们使用aspnet6.0作为基础包&#xff0c;则有2个选择 mcr.microsoft.com/dotnet/aspnet:6.0 212MB (basic) mcr.microsoft.com/dotnet/aspnet:6.0-alpine 104MB (alpine) 问题回顾 目前的Past…

小红书种草怎么做?

文末领取小红书电商开店运营教程&#xff01; 在如今的社交电商时代&#xff0c;小红书作为国内最大的生活分享社区&#xff0c;已成为了许多人找寻新品、新店、新玩法的必选平台。 小红书上的“种草”文化也日渐盛行&#xff0c;它不仅仅是一个购物指南&#xff0c;更是一种…

Python3极简教程(一小时学完)下

目录 PEP8 代码风格指南 知识点 介绍 愚蠢的一致性就像没脑子的妖怪 代码排版 缩进 制表符还是空格 每行最大长度 空行 源文件编码 导入包 字符串引号 表达式和语句中的空格 不能忍受的情况 其他建议 注释 块注释 行内注释 文档字符串 版本注记 命名约定 …

索引结构与检索原理

一、mysql索引结构 1.BTree索引 [检索原理] 左边列的表格&#xff08;真实数据&#xff09;&#xff0c;右边对应一棵树&#xff0c;树的管度越来越管查询越快。 以下图表的名称为&#xff1a;段区块 硬盘都是长方形的&#xff0c;打了一个封装&#xff0c;里面是一个圆圈…

游戏热更新——AssetBundle

AssetBundle AssetBundle的定义与使用 AssetBundle是一个压缩包包含模型、贴图、预制体、声音、甚至是整个场景&#xff0c;可以在游戏运行的时候被加载 AssetBundle自身保存着相互的依赖关系 压缩包可以使用LZMA和LZ4压缩算法&#xff0c;减少包大小&#xff0c;更快的进行网…

栈(Stack)and leetcode刷题

栈&#xff08;Stack&#xff09;and leetcode刷题 1. 栈&#xff08;Stack&#xff09;的概念2. 栈&#xff08;Stack&#xff09;的实现2.1 用数组实现2.2 用链表实现2.2.1 用单链表实现 3. leetcode刷题3.1 括号匹配问题3.2 栈的弹出压入序列3.3 逆波兰表达式求值中缀表达式…

Cartographer重入门到精通(二):运行作者demo及自己的数据集

在demo数据包上运行cartographer 现在Cartographer和Cartographer的Ros包已经都安装好了&#xff0c;你可以下载官方的数据集到指定的目录&#xff08;比如在Deutsches Museum用背包采集的2D和3D 数据&#xff09;&#xff0c;然后使用roslauch来启动demo。 注&#xff1a;la…

一文了解5G新通话技术演进与业务模型

5G新通话简介 5G新通话&#xff0c;也被称为VoNR&#xff0c;是基于R16及后续协议产生的一种增强型语音通话业务。 它在IMS网络里新增数据通道&#xff08;Data Channel&#xff09;&#xff0c;承载通话时的文本、图片、涂鸦、菜单等信息。它能在传统话音业务基础上提供更多服…

拓扑排序——AcWing 164. 可达性统计

目录 拓扑排序 定义 运用情况 注意事项 解题思路 AcWing 164. 可达性统计 题目描述 运行代码 代码思路 改进思路 拓扑排序 定义 拓扑排序&#xff08;Topological Sort&#xff09;是对有向无环图&#xff08;Directed Acyclic Graph&#xff0c;简称DAG&#xff…

【论文阅读笔记】ASPS: Augmented Segment Anything Model for Polyp Segmentation

1.论文介绍 ASPS: Augmented Segment Anything Model for Polyp Segmentation ASPS&#xff1a;用于息肉分割的扩展SAM模型 2024年 arxiv Paper Code 2.摘要 息肉分割在结直肠癌诊断中起着至关重要的作用。最近&#xff0c;Segment Anything Model(SAM)的出现利用其在大规模…

去水印小程序源码修复版-前端后端内置接口+第三方接口

去水印小程序源码&#xff0c;前端后端&#xff0c;内置接口第三方接口&#xff0c; 修复数据库账号密码错误问题&#xff0c;内置接口支持替换第三方接口&#xff0c; 文件挺全的&#xff0c;可以添加流量主代码&#xff0c;搭建需要准备一台服务器&#xff0c;备案域名和http…

【JVM实战篇】内存调优:内存问题诊断+案例实战

文章目录 诊断内存快照在内存溢出时生成内存快照MAT分析内存快照MAT内存泄漏检测的原理支配树介绍如何在不内存溢出情况下生成堆内存快照&#xff1f;MAT查看支配树MAT如何根据支配树发现内存泄漏 运行程序的内存快照导出和分析快照**大文件的处理** 案例实战案例1&#xff1a;…

交换机和路由器的工作流程

1、交换机工作流程&#xff1a; 将接口中的电流识别为二进制&#xff0c;并转换成数据帧&#xff0c;交换机会记录学习该数据帧的源MAC地址&#xff0c;并将其端口关联起来记录在MAC地址表中。然后查看MAC地址表来查找目标MAC地址&#xff0c;会有一下一些情况&#xff1a; MA…

java.sql.SQLException: Before start of result set

情况描述&#xff0c;在通过JDBC连接数据库时&#xff0c;想直接判断获取的值是否存在&#xff0c;运行时报错。 翻译&#xff1a; 在开始结果集之前 报错截图 解决问题的方法&#xff1a;对结果集ResultSet进行操作之前&#xff0c;一定要先用ResultSet.next()将指针移动至…

4K60无缝一体矩阵 HDMI2.0功能介绍

关于GF-HDMI0808S 4K60无缝一体矩阵的功能介绍&#xff0c;由于直接针对GF-HDMI0808S型号的具体信息较少&#xff0c;我将结合类似4K60无缝HDMI矩阵的一般功能特性和可能的GF-HDMI0808系列产品的特点来进行说明。请注意&#xff0c;以下信息可能不完全针对GF-HDMI0808S型号&…

vienna整流器的矢量分析

Vienna整流器使用六个二极管和六个IGBT&#xff08;或MOSFET&#xff09;组成&#xff0c;提供三个电平&#xff1a;正极电平&#xff08;P&#xff09;、中性点电平&#xff08;O&#xff09;和负极电平&#xff08;N&#xff09;。通过对功率管的控制&#xff0c;Vienna整流器…

xmind梳理测试点,根据这些测试点去写测试用例

基本流&#xff08;冒烟用例必写&#xff09; 备选流 公共测试点&#xff1a;