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

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.mfbz.cn/a/796792.html

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

MUR2060CTR-ASEMI无人机专用MUR2060CTR

编辑&#xff1a;ll MUR2060CTR-ASEMI无人机专用MUR2060CTR 型号&#xff1a;MUR2060CTR 品牌&#xff1a;ASEMI 封装&#xff1a;TO-220 批号&#xff1a;最新 最大平均正向电流&#xff08;IF&#xff09;&#xff1a;20A 最大循环峰值反向电压&#xff08;VRRM&#…

tkinter-TinUI-xml实战(12)pip可视化管理器

引言 pip命令行工具在平常使用方面确实足够简单&#xff0c;本项目只是作为TinUI多界面开发的示例。 当然&#xff0c;总有人想用GUI版pip&#xff0c;实际上也有。不过现在&#xff0c;我们就来手搓一个基于python和TinUI&#xff08;tkinter&#xff09;的pip可视化管理器。…

线程控制

对线程的控制思路和进程相似&#xff0c;创建、等待、终止&#xff0c;只需要调用接口就行。但是在Linux下没有线程的概念&#xff0c;因为Linux的设计者认为&#xff0c;线程是一种轻量级的进程&#xff0c;毕竟创建线程只需要创建PCB。因此Linux中使用多线程必须使用第三方pt…

深入Linux:权限管理与常用命令详解

文章目录 ❤️Linux常用指令&#x1fa77;zip/unzip指令&#x1fa77;tar指令&#x1fa77;bc指令&#x1fa77;uname指令&#x1fa77;shutdown指令 ❤️shell命令以及原理❤️什么是 Shell 命令❤️Linux权限管理的概念❤️Linux权限管理&#x1fa77;文件访问者的分类&#…

深度学习中的FLOPs补充

学习了博主的介绍&#xff08;深度学习中的FLOPs介绍及计算(注意区分FLOPS)-CSDN博客&#xff09;后&#xff0c;对我不理解的内容做了一点补充。 链接放到下边啦 https://blog.csdn.net/qq_41834400/article/details/120283103 FLOPs&#xff1a;注意s小写&#xff0c;是floa…

车流量统计YOLOV8+DEEPSORT

车流量统计&#xff0c;YOLOV8NANODEEPSORT资源-CSDN文库 车流量统计YOLOV8DEEPSORT&#xff0c;目前支持PYTHON,C开发 PYTHON版本&#xff0c;需要YOLOV8&#xff0c;依赖PYTORCH C版本&#xff0c;只需要OPENCV

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

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

【Vscode】显示多个文件 打开多个文件时实现标签栏多行显示

Vscode显示多个文件&VSCode打开多个文件时实现标签栏多行显示 写在最前面一、解决打开文件的时候只显示一个tab的办法解决办法如下&#xff1a; 二、文件标签栏多行显示设置步骤&#xff1a; &#x1f308;你好呀&#xff01;我是 是Yu欸 &#x1f30c; 2024每日百字篆刻时…

记录些Redis题集(3)

分布式锁 分布式锁是一种用于在分布式系统中实现互斥访问的机制&#xff0c;它可以确保在多个节点、或进程同时访问共享资源。如果没有适当的锁机制&#xff0c;就可能导致数据不一致或并发冲突的问题。 分布式锁需要的介质 需要一个多个微服务节点都能访问的存储介质&#…

实战演练-2021年电赛国一之三端口DC-DC变换器

文章目录 前言一、题目二、题目分析1、题目要求解析2、题目方案选定方案一(使用buck-boost电路&#xff0b;双向DC-DC电路&#xff08;前端&#xff09;)方案二(使用同步整流Boost升压电路&#xff0b;双向DC-DC电路&#xff08;前端&#xff09;)方案三(使用同步整流Boost升压…

打造你的智能家居指挥中心:基于STM32的多协议(zigbee、http)网关(附代码示例)

1. 项目概述 随着物联网技术的蓬勃发展&#xff0c;智能家居正逐步融入人们的日常生活。然而&#xff0c;市面上琳琅满目的智能家居设备通常采用不同的通信协议&#xff0c;导致不同品牌设备之间难以实现互联互通。为了解决这一难题&#xff0c;本文设计了一种基于STM32的多协…

我的AI音乐梦:ChatGPT帮我做专辑

​&#x1f308;个人主页&#xff1a;前端青山 &#x1f525;系列专栏&#xff1a;AI篇 &#x1f516;人终将被年少不可得之物困其一生 依旧青山,本期给大家带来ChatGPT帮我做音乐专辑 嘿&#xff0c;朋友们&#xff01; 想象一下&#xff0c;如果有个超级聪明的机器人能帮你写…

【Unity学习笔记】第十九 · 物理引擎约束求解解惑(LCP,最优,拉格朗日乘数法,SI,PGS,基于冲量法)

转载请注明出处: https://blog.csdn.net/weixin_44013533/article/details/140309494 作者&#xff1a;CSDN|Ringleader| 在学习物理引擎过程中&#xff0c;有几大问题一直困扰着我&#xff1a; 约束求解到底是LCP还是带约束最优问题&#xff1f;约束求解过程中拉格朗日乘数法…

春招冲刺百题计划|堆

Java基础复习 Java数组的声明与初始化Java ArrayListJava HashMapJava String 类Java LinkedListJava Deque继承LinkedListJava SetJava 队列优先队列:第二题用到了 第一题&#xff1a;215. 数组中的第K个最大元素 可以直接使用Arrays.sort()快排&#xff0c;然后return nums…

修正版头像上传组件

修正版头像上传组件 文章说明核心源码展示运行效果展示源码下载 文章说明 在头像剪切上传一文中&#xff0c;我采用div做裁剪效果&#xff0c;感觉会有一些小问题&#xff0c;在昨天基于canvas绘制的功能中改进了一版&#xff0c;让代码变得更简洁&#xff0c;而且通用性相对高…

ChatGPT使用姿势

使用上的痛点 用的不好&#xff1a;你经常会感觉到 ChatGPT 回答的好空&#xff0c;没有太多参考价值无处去用&#xff1a;有了 GPT 之后&#xff0c;发现自己好像并没有什么好问的&#xff0c;不知道可以用 GPT 来干嘛。 如何使用AI 核心心法&#xff1a;GPT 生成的答案质量…

纯技术分享:淘宝商品详情原数据接口参数解析

item_get_app-获得淘宝app商品详情原数据 公共参数 名称类型必须描述keyString是调用key&#xff08;必须以GET方式拼接在URL中&#xff09;secretString是调用密钥api_nameString是API接口名称&#xff08;包括在请求地址中&#xff09;[item_search,item_get,item_search_s…

【机器学习】使用决策树分类器预测汽车安全性的研究与分析

文章目录 一、决策树算法简介决策树的结构分类和回归树 (CART)决策树算法术语决策树算法直觉 二、属性选择度量信息增益熵 基尼指数计算分割基尼指数的步骤 三、决策树算法中的过度拟合避免过度拟合的方法 四、导入库和数据可视化探索性数据分析重命名列名查看数据集的总结信息…

WAF基础介绍

WAF 一、WAF是什么&#xff1f;WAF能够做什么 二 waf的部署三、WAF的工作原理 一、WAF是什么&#xff1f; WAF的全称是&#xff08;Web Application Firewall&#xff09;即Web应用防火墙&#xff0c;简称WAF。 国际上公认的一种说法是&#xff1a;Web应用防火墙是通过执行一…

小零食,大智慧!连锁零食店如何选择收银?收银系统源码

近几年专业的散装零食店非常的火热&#xff0c;像百草味、良品铺子、大嘴零食、来伊份等都大受欢迎。而传统超市的散装零食区则是日益冷落&#xff0c;小超市多数干脆放弃了散装。 休闲零食作为快消品的一类&#xff0c;是大家工作闲暇、生活休闲的必备食品。随着人们生活质量…